1#![doc = "MAVLink common dialect."]
2#![doc = ""]
3#![doc = "This file was automatically generated, do not edit."]
4#![allow(deprecated)]
5#![allow(clippy::match_single_binding)]
6#[cfg(feature = "arbitrary")]
7use arbitrary::Arbitrary;
8#[allow(unused_imports)]
9use bitflags::{bitflags, Flags};
10#[allow(unused_imports)]
11use mavlink_core::{
12 bytes::Bytes, bytes_mut::BytesMut, types::CharArray, MavlinkVersion, Message, MessageData,
13};
14#[allow(unused_imports)]
15use num_derive::{FromPrimitive, ToPrimitive};
16#[allow(unused_imports)]
17use num_traits::{FromPrimitive, ToPrimitive};
18#[cfg(feature = "serde")]
19use serde::{Deserialize, Serialize};
20#[cfg(feature = "ts")]
21use ts_rs::TS;
22pub const MINOR_MAVLINK_VERSION: u8 = 3u8;
23pub const DIALECT_NUMBER: u8 = 0u8;
24#[cfg_attr(feature = "ts", derive(TS))]
25#[cfg_attr(feature = "ts", ts(export))]
26#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
27#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28#[cfg_attr(feature = "serde", serde(tag = "type"))]
29#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30#[repr(u32)]
31#[doc = "Actuator configuration, used to change a setting on an actuator. Component information metadata can be used to know which outputs support which commands."]
32pub enum ActuatorConfiguration {
33 #[doc = "Do nothing."]
34 ACTUATOR_CONFIGURATION_NONE = 0,
35 #[doc = "Command the actuator to beep now."]
36 ACTUATOR_CONFIGURATION_BEEP = 1,
37 #[doc = "Permanently set the actuator (ESC) to 3D mode (reversible thrust)."]
38 ACTUATOR_CONFIGURATION_3D_MODE_ON = 2,
39 #[doc = "Permanently set the actuator (ESC) to non 3D mode (non-reversible thrust)."]
40 ACTUATOR_CONFIGURATION_3D_MODE_OFF = 3,
41 #[doc = "Permanently set the actuator (ESC) to spin direction 1 (which can be clockwise or counter-clockwise)."]
42 ACTUATOR_CONFIGURATION_SPIN_DIRECTION1 = 4,
43 #[doc = "Permanently set the actuator (ESC) to spin direction 2 (opposite of direction 1)."]
44 ACTUATOR_CONFIGURATION_SPIN_DIRECTION2 = 5,
45}
46impl ActuatorConfiguration {
47 pub const DEFAULT: Self = Self::ACTUATOR_CONFIGURATION_NONE;
48}
49impl Default for ActuatorConfiguration {
50 fn default() -> Self {
51 Self::DEFAULT
52 }
53}
54#[cfg_attr(feature = "ts", derive(TS))]
55#[cfg_attr(feature = "ts", ts(export))]
56#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
57#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
58#[cfg_attr(feature = "serde", serde(tag = "type"))]
59#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
60#[repr(u32)]
61#[doc = "Actuator output function. Values greater or equal to 1000 are autopilot-specific."]
62pub enum ActuatorOutputFunction {
63 #[doc = "No function (disabled)."]
64 ACTUATOR_OUTPUT_FUNCTION_NONE = 0,
65 #[doc = "Motor 1"]
66 ACTUATOR_OUTPUT_FUNCTION_MOTOR1 = 1,
67 #[doc = "Motor 2"]
68 ACTUATOR_OUTPUT_FUNCTION_MOTOR2 = 2,
69 #[doc = "Motor 3"]
70 ACTUATOR_OUTPUT_FUNCTION_MOTOR3 = 3,
71 #[doc = "Motor 4"]
72 ACTUATOR_OUTPUT_FUNCTION_MOTOR4 = 4,
73 #[doc = "Motor 5"]
74 ACTUATOR_OUTPUT_FUNCTION_MOTOR5 = 5,
75 #[doc = "Motor 6"]
76 ACTUATOR_OUTPUT_FUNCTION_MOTOR6 = 6,
77 #[doc = "Motor 7"]
78 ACTUATOR_OUTPUT_FUNCTION_MOTOR7 = 7,
79 #[doc = "Motor 8"]
80 ACTUATOR_OUTPUT_FUNCTION_MOTOR8 = 8,
81 #[doc = "Motor 9"]
82 ACTUATOR_OUTPUT_FUNCTION_MOTOR9 = 9,
83 #[doc = "Motor 10"]
84 ACTUATOR_OUTPUT_FUNCTION_MOTOR10 = 10,
85 #[doc = "Motor 11"]
86 ACTUATOR_OUTPUT_FUNCTION_MOTOR11 = 11,
87 #[doc = "Motor 12"]
88 ACTUATOR_OUTPUT_FUNCTION_MOTOR12 = 12,
89 #[doc = "Motor 13"]
90 ACTUATOR_OUTPUT_FUNCTION_MOTOR13 = 13,
91 #[doc = "Motor 14"]
92 ACTUATOR_OUTPUT_FUNCTION_MOTOR14 = 14,
93 #[doc = "Motor 15"]
94 ACTUATOR_OUTPUT_FUNCTION_MOTOR15 = 15,
95 #[doc = "Motor 16"]
96 ACTUATOR_OUTPUT_FUNCTION_MOTOR16 = 16,
97 #[doc = "Servo 1"]
98 ACTUATOR_OUTPUT_FUNCTION_SERVO1 = 33,
99 #[doc = "Servo 2"]
100 ACTUATOR_OUTPUT_FUNCTION_SERVO2 = 34,
101 #[doc = "Servo 3"]
102 ACTUATOR_OUTPUT_FUNCTION_SERVO3 = 35,
103 #[doc = "Servo 4"]
104 ACTUATOR_OUTPUT_FUNCTION_SERVO4 = 36,
105 #[doc = "Servo 5"]
106 ACTUATOR_OUTPUT_FUNCTION_SERVO5 = 37,
107 #[doc = "Servo 6"]
108 ACTUATOR_OUTPUT_FUNCTION_SERVO6 = 38,
109 #[doc = "Servo 7"]
110 ACTUATOR_OUTPUT_FUNCTION_SERVO7 = 39,
111 #[doc = "Servo 8"]
112 ACTUATOR_OUTPUT_FUNCTION_SERVO8 = 40,
113 #[doc = "Servo 9"]
114 ACTUATOR_OUTPUT_FUNCTION_SERVO9 = 41,
115 #[doc = "Servo 10"]
116 ACTUATOR_OUTPUT_FUNCTION_SERVO10 = 42,
117 #[doc = "Servo 11"]
118 ACTUATOR_OUTPUT_FUNCTION_SERVO11 = 43,
119 #[doc = "Servo 12"]
120 ACTUATOR_OUTPUT_FUNCTION_SERVO12 = 44,
121 #[doc = "Servo 13"]
122 ACTUATOR_OUTPUT_FUNCTION_SERVO13 = 45,
123 #[doc = "Servo 14"]
124 ACTUATOR_OUTPUT_FUNCTION_SERVO14 = 46,
125 #[doc = "Servo 15"]
126 ACTUATOR_OUTPUT_FUNCTION_SERVO15 = 47,
127 #[doc = "Servo 16"]
128 ACTUATOR_OUTPUT_FUNCTION_SERVO16 = 48,
129}
130impl ActuatorOutputFunction {
131 pub const DEFAULT: Self = Self::ACTUATOR_OUTPUT_FUNCTION_NONE;
132}
133impl Default for ActuatorOutputFunction {
134 fn default() -> Self {
135 Self::DEFAULT
136 }
137}
138#[cfg_attr(feature = "ts", derive(TS))]
139#[cfg_attr(feature = "ts", ts(export))]
140#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
141#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
142#[cfg_attr(feature = "serde", serde(tag = "type"))]
143#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
144#[repr(u32)]
145#[doc = "Enumeration of the ADSB altimeter types"]
146pub enum AdsbAltitudeType {
147 #[doc = "Altitude reported from a Baro source using QNH reference"]
148 ADSB_ALTITUDE_TYPE_PRESSURE_QNH = 0,
149 #[doc = "Altitude reported from a GNSS source"]
150 ADSB_ALTITUDE_TYPE_GEOMETRIC = 1,
151}
152impl AdsbAltitudeType {
153 pub const DEFAULT: Self = Self::ADSB_ALTITUDE_TYPE_PRESSURE_QNH;
154}
155impl Default for AdsbAltitudeType {
156 fn default() -> Self {
157 Self::DEFAULT
158 }
159}
160#[cfg_attr(feature = "ts", derive(TS))]
161#[cfg_attr(feature = "ts", ts(export))]
162#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
163#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
164#[cfg_attr(feature = "serde", serde(tag = "type"))]
165#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
166#[repr(u32)]
167#[doc = "ADSB classification for the type of vehicle emitting the transponder signal"]
168pub enum AdsbEmitterType {
169 ADSB_EMITTER_TYPE_NO_INFO = 0,
170 ADSB_EMITTER_TYPE_LIGHT = 1,
171 ADSB_EMITTER_TYPE_SMALL = 2,
172 ADSB_EMITTER_TYPE_LARGE = 3,
173 ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE = 4,
174 ADSB_EMITTER_TYPE_HEAVY = 5,
175 ADSB_EMITTER_TYPE_HIGHLY_MANUV = 6,
176 ADSB_EMITTER_TYPE_ROTOCRAFT = 7,
177 ADSB_EMITTER_TYPE_UNASSIGNED = 8,
178 ADSB_EMITTER_TYPE_GLIDER = 9,
179 ADSB_EMITTER_TYPE_LIGHTER_AIR = 10,
180 ADSB_EMITTER_TYPE_PARACHUTE = 11,
181 ADSB_EMITTER_TYPE_ULTRA_LIGHT = 12,
182 ADSB_EMITTER_TYPE_UNASSIGNED2 = 13,
183 ADSB_EMITTER_TYPE_UAV = 14,
184 ADSB_EMITTER_TYPE_SPACE = 15,
185 ADSB_EMITTER_TYPE_UNASSGINED3 = 16,
186 ADSB_EMITTER_TYPE_EMERGENCY_SURFACE = 17,
187 ADSB_EMITTER_TYPE_SERVICE_SURFACE = 18,
188 ADSB_EMITTER_TYPE_POINT_OBSTACLE = 19,
189}
190impl AdsbEmitterType {
191 pub const DEFAULT: Self = Self::ADSB_EMITTER_TYPE_NO_INFO;
192}
193impl Default for AdsbEmitterType {
194 fn default() -> Self {
195 Self::DEFAULT
196 }
197}
198bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These flags indicate status such as data validity of each data source. Set = data valid"] pub struct AdsbFlags : u16 { const ADSB_FLAGS_VALID_COORDS = 1 ; const ADSB_FLAGS_VALID_ALTITUDE = 2 ; const ADSB_FLAGS_VALID_HEADING = 4 ; const ADSB_FLAGS_VALID_VELOCITY = 8 ; const ADSB_FLAGS_VALID_CALLSIGN = 16 ; const ADSB_FLAGS_VALID_SQUAWK = 32 ; const ADSB_FLAGS_SIMULATED = 64 ; const ADSB_FLAGS_VERTICAL_VELOCITY_VALID = 128 ; const ADSB_FLAGS_BARO_VALID = 256 ; const ADSB_FLAGS_SOURCE_UAT = 32768 ; } }
199impl AdsbFlags {
200 pub const DEFAULT: Self = Self::ADSB_FLAGS_VALID_COORDS;
201}
202impl Default for AdsbFlags {
203 fn default() -> Self {
204 Self::DEFAULT
205 }
206}
207bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These flags are used in the AIS_VESSEL.fields bitmask to indicate validity of data in the other message fields. When set, the data is valid."] pub struct AisFlags : u16 { # [doc = "1 = Position accuracy less than 10m, 0 = position accuracy greater than 10m."] const AIS_FLAGS_POSITION_ACCURACY = 1 ; const AIS_FLAGS_VALID_COG = 2 ; const AIS_FLAGS_VALID_VELOCITY = 4 ; # [doc = "1 = Velocity over 52.5765m/s (102.2 knots)"] const AIS_FLAGS_HIGH_VELOCITY = 8 ; const AIS_FLAGS_VALID_TURN_RATE = 16 ; # [doc = "Only the sign of the returned turn rate value is valid, either greater than 5deg/30s or less than -5deg/30s"] const AIS_FLAGS_TURN_RATE_SIGN_ONLY = 32 ; const AIS_FLAGS_VALID_DIMENSIONS = 64 ; # [doc = "Distance to bow is larger than 511m"] const AIS_FLAGS_LARGE_BOW_DIMENSION = 128 ; # [doc = "Distance to stern is larger than 511m"] const AIS_FLAGS_LARGE_STERN_DIMENSION = 256 ; # [doc = "Distance to port side is larger than 63m"] const AIS_FLAGS_LARGE_PORT_DIMENSION = 512 ; # [doc = "Distance to starboard side is larger than 63m"] const AIS_FLAGS_LARGE_STARBOARD_DIMENSION = 1024 ; const AIS_FLAGS_VALID_CALLSIGN = 2048 ; const AIS_FLAGS_VALID_NAME = 4096 ; } }
208impl AisFlags {
209 pub const DEFAULT: Self = Self::AIS_FLAGS_POSITION_ACCURACY;
210}
211impl Default for AisFlags {
212 fn default() -> Self {
213 Self::DEFAULT
214 }
215}
216#[cfg_attr(feature = "ts", derive(TS))]
217#[cfg_attr(feature = "ts", ts(export))]
218#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
219#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
220#[cfg_attr(feature = "serde", serde(tag = "type"))]
221#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
222#[repr(u32)]
223#[doc = "Navigational status of AIS vessel, enum duplicated from AIS standard, <https://gpsd.gitlab.io/gpsd/AIVDM.html>"]
224pub enum AisNavStatus {
225 #[doc = "Under way using engine."]
226 UNDER_WAY = 0,
227 AIS_NAV_ANCHORED = 1,
228 AIS_NAV_UN_COMMANDED = 2,
229 AIS_NAV_RESTRICTED_MANOEUVERABILITY = 3,
230 AIS_NAV_DRAUGHT_CONSTRAINED = 4,
231 AIS_NAV_MOORED = 5,
232 AIS_NAV_AGROUND = 6,
233 AIS_NAV_FISHING = 7,
234 AIS_NAV_SAILING = 8,
235 AIS_NAV_RESERVED_HSC = 9,
236 AIS_NAV_RESERVED_WIG = 10,
237 AIS_NAV_RESERVED_1 = 11,
238 AIS_NAV_RESERVED_2 = 12,
239 AIS_NAV_RESERVED_3 = 13,
240 #[doc = "Search And Rescue Transponder."]
241 AIS_NAV_AIS_SART = 14,
242 #[doc = "Not available (default)."]
243 AIS_NAV_UNKNOWN = 15,
244}
245impl AisNavStatus {
246 pub const DEFAULT: Self = Self::UNDER_WAY;
247}
248impl Default for AisNavStatus {
249 fn default() -> Self {
250 Self::DEFAULT
251 }
252}
253#[cfg_attr(feature = "ts", derive(TS))]
254#[cfg_attr(feature = "ts", ts(export))]
255#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
256#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
257#[cfg_attr(feature = "serde", serde(tag = "type"))]
258#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
259#[repr(u32)]
260#[doc = "Type of AIS vessel, enum duplicated from AIS standard, <https://gpsd.gitlab.io/gpsd/AIVDM.html>"]
261pub enum AisType {
262 #[doc = "Not available (default)."]
263 AIS_TYPE_UNKNOWN = 0,
264 AIS_TYPE_RESERVED_1 = 1,
265 AIS_TYPE_RESERVED_2 = 2,
266 AIS_TYPE_RESERVED_3 = 3,
267 AIS_TYPE_RESERVED_4 = 4,
268 AIS_TYPE_RESERVED_5 = 5,
269 AIS_TYPE_RESERVED_6 = 6,
270 AIS_TYPE_RESERVED_7 = 7,
271 AIS_TYPE_RESERVED_8 = 8,
272 AIS_TYPE_RESERVED_9 = 9,
273 AIS_TYPE_RESERVED_10 = 10,
274 AIS_TYPE_RESERVED_11 = 11,
275 AIS_TYPE_RESERVED_12 = 12,
276 AIS_TYPE_RESERVED_13 = 13,
277 AIS_TYPE_RESERVED_14 = 14,
278 AIS_TYPE_RESERVED_15 = 15,
279 AIS_TYPE_RESERVED_16 = 16,
280 AIS_TYPE_RESERVED_17 = 17,
281 AIS_TYPE_RESERVED_18 = 18,
282 AIS_TYPE_RESERVED_19 = 19,
283 #[doc = "Wing In Ground effect."]
284 AIS_TYPE_WIG = 20,
285 AIS_TYPE_WIG_HAZARDOUS_A = 21,
286 AIS_TYPE_WIG_HAZARDOUS_B = 22,
287 AIS_TYPE_WIG_HAZARDOUS_C = 23,
288 AIS_TYPE_WIG_HAZARDOUS_D = 24,
289 AIS_TYPE_WIG_RESERVED_1 = 25,
290 AIS_TYPE_WIG_RESERVED_2 = 26,
291 AIS_TYPE_WIG_RESERVED_3 = 27,
292 AIS_TYPE_WIG_RESERVED_4 = 28,
293 AIS_TYPE_WIG_RESERVED_5 = 29,
294 AIS_TYPE_FISHING = 30,
295 AIS_TYPE_TOWING = 31,
296 #[doc = "Towing: length exceeds 200m or breadth exceeds 25m."]
297 AIS_TYPE_TOWING_LARGE = 32,
298 #[doc = "Dredging or other underwater ops."]
299 AIS_TYPE_DREDGING = 33,
300 AIS_TYPE_DIVING = 34,
301 AIS_TYPE_MILITARY = 35,
302 AIS_TYPE_SAILING = 36,
303 AIS_TYPE_PLEASURE = 37,
304 AIS_TYPE_RESERVED_20 = 38,
305 AIS_TYPE_RESERVED_21 = 39,
306 #[doc = "High Speed Craft."]
307 AIS_TYPE_HSC = 40,
308 AIS_TYPE_HSC_HAZARDOUS_A = 41,
309 AIS_TYPE_HSC_HAZARDOUS_B = 42,
310 AIS_TYPE_HSC_HAZARDOUS_C = 43,
311 AIS_TYPE_HSC_HAZARDOUS_D = 44,
312 AIS_TYPE_HSC_RESERVED_1 = 45,
313 AIS_TYPE_HSC_RESERVED_2 = 46,
314 AIS_TYPE_HSC_RESERVED_3 = 47,
315 AIS_TYPE_HSC_RESERVED_4 = 48,
316 AIS_TYPE_HSC_UNKNOWN = 49,
317 AIS_TYPE_PILOT = 50,
318 #[doc = "Search And Rescue vessel."]
319 AIS_TYPE_SAR = 51,
320 AIS_TYPE_TUG = 52,
321 AIS_TYPE_PORT_TENDER = 53,
322 #[doc = "Anti-pollution equipment."]
323 AIS_TYPE_ANTI_POLLUTION = 54,
324 AIS_TYPE_LAW_ENFORCEMENT = 55,
325 AIS_TYPE_SPARE_LOCAL_1 = 56,
326 AIS_TYPE_SPARE_LOCAL_2 = 57,
327 AIS_TYPE_MEDICAL_TRANSPORT = 58,
328 #[doc = "Noncombatant ship according to RR Resolution No. 18."]
329 AIS_TYPE_NONECOMBATANT = 59,
330 AIS_TYPE_PASSENGER = 60,
331 AIS_TYPE_PASSENGER_HAZARDOUS_A = 61,
332 AIS_TYPE_PASSENGER_HAZARDOUS_B = 62,
333 AIS_TYPE_PASSENGER_HAZARDOUS_C = 63,
334 AIS_TYPE_PASSENGER_HAZARDOUS_D = 64,
335 AIS_TYPE_PASSENGER_RESERVED_1 = 65,
336 AIS_TYPE_PASSENGER_RESERVED_2 = 66,
337 AIS_TYPE_PASSENGER_RESERVED_3 = 67,
338 AIS_TYPE_PASSENGER_RESERVED_4 = 68,
339 AIS_TYPE_PASSENGER_UNKNOWN = 69,
340 AIS_TYPE_CARGO = 70,
341 AIS_TYPE_CARGO_HAZARDOUS_A = 71,
342 AIS_TYPE_CARGO_HAZARDOUS_B = 72,
343 AIS_TYPE_CARGO_HAZARDOUS_C = 73,
344 AIS_TYPE_CARGO_HAZARDOUS_D = 74,
345 AIS_TYPE_CARGO_RESERVED_1 = 75,
346 AIS_TYPE_CARGO_RESERVED_2 = 76,
347 AIS_TYPE_CARGO_RESERVED_3 = 77,
348 AIS_TYPE_CARGO_RESERVED_4 = 78,
349 AIS_TYPE_CARGO_UNKNOWN = 79,
350 AIS_TYPE_TANKER = 80,
351 AIS_TYPE_TANKER_HAZARDOUS_A = 81,
352 AIS_TYPE_TANKER_HAZARDOUS_B = 82,
353 AIS_TYPE_TANKER_HAZARDOUS_C = 83,
354 AIS_TYPE_TANKER_HAZARDOUS_D = 84,
355 AIS_TYPE_TANKER_RESERVED_1 = 85,
356 AIS_TYPE_TANKER_RESERVED_2 = 86,
357 AIS_TYPE_TANKER_RESERVED_3 = 87,
358 AIS_TYPE_TANKER_RESERVED_4 = 88,
359 AIS_TYPE_TANKER_UNKNOWN = 89,
360 AIS_TYPE_OTHER = 90,
361 AIS_TYPE_OTHER_HAZARDOUS_A = 91,
362 AIS_TYPE_OTHER_HAZARDOUS_B = 92,
363 AIS_TYPE_OTHER_HAZARDOUS_C = 93,
364 AIS_TYPE_OTHER_HAZARDOUS_D = 94,
365 AIS_TYPE_OTHER_RESERVED_1 = 95,
366 AIS_TYPE_OTHER_RESERVED_2 = 96,
367 AIS_TYPE_OTHER_RESERVED_3 = 97,
368 AIS_TYPE_OTHER_RESERVED_4 = 98,
369 AIS_TYPE_OTHER_UNKNOWN = 99,
370}
371impl AisType {
372 pub const DEFAULT: Self = Self::AIS_TYPE_UNKNOWN;
373}
374impl Default for AisType {
375 fn default() -> Self {
376 Self::DEFAULT
377 }
378}
379bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates that none of the setpoint dimensions should be ignored."] pub struct AttitudeTargetTypemask : u8 { # [doc = "Ignore body roll rate"] const ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE = 1 ; # [doc = "Ignore body pitch rate"] const ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE = 2 ; # [doc = "Ignore body yaw rate"] const ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE = 4 ; # [doc = "Use 3D body thrust setpoint instead of throttle"] const ATTITUDE_TARGET_TYPEMASK_THRUST_BODY_SET = 32 ; # [doc = "Ignore throttle"] const ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE = 64 ; # [doc = "Ignore attitude"] const ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE = 128 ; } }
380impl AttitudeTargetTypemask {
381 pub const DEFAULT: Self = Self::ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE;
382}
383impl Default for AttitudeTargetTypemask {
384 fn default() -> Self {
385 Self::DEFAULT
386 }
387}
388#[cfg_attr(feature = "ts", derive(TS))]
389#[cfg_attr(feature = "ts", ts(export))]
390#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
391#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
392#[cfg_attr(feature = "serde", serde(tag = "type"))]
393#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
394#[repr(u32)]
395#[doc = "Axes that will be autotuned by MAV_CMD_DO_AUTOTUNE_ENABLE. Note that at least one flag must be set in MAV_CMD_DO_AUTOTUNE_ENABLE.param2: if none are set, the flight stack will tune its default set of axes."]
396pub enum AutotuneAxis {
397 #[doc = "Autotune roll axis."]
398 AUTOTUNE_AXIS_ROLL = 1,
399 #[doc = "Autotune pitch axis."]
400 AUTOTUNE_AXIS_PITCH = 2,
401 #[doc = "Autotune yaw axis."]
402 AUTOTUNE_AXIS_YAW = 4,
403}
404impl AutotuneAxis {
405 pub const DEFAULT: Self = Self::AUTOTUNE_AXIS_ROLL;
406}
407impl Default for AutotuneAxis {
408 fn default() -> Self {
409 Self::DEFAULT
410 }
411}
412bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Camera capability flags (Bitmap)"] pub struct CameraCapFlags : u32 { # [doc = "Camera is able to record video"] const CAMERA_CAP_FLAGS_CAPTURE_VIDEO = 1 ; # [doc = "Camera is able to capture images"] const CAMERA_CAP_FLAGS_CAPTURE_IMAGE = 2 ; # [doc = "Camera has separate Video and Image/Photo modes (MAV_CMD_SET_CAMERA_MODE)"] const CAMERA_CAP_FLAGS_HAS_MODES = 4 ; # [doc = "Camera can capture images while in video mode"] const CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE = 8 ; # [doc = "Camera can capture videos while in Photo/Image mode"] const CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE = 16 ; # [doc = "Camera has image survey mode (MAV_CMD_SET_CAMERA_MODE)"] const CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE = 32 ; # [doc = "Camera has basic zoom control (MAV_CMD_SET_CAMERA_ZOOM)"] const CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM = 64 ; # [doc = "Camera has basic focus control (MAV_CMD_SET_CAMERA_FOCUS)"] const CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS = 128 ; # [doc = "Camera has video streaming capabilities (request VIDEO_STREAM_INFORMATION with MAV_CMD_REQUEST_MESSAGE for video streaming info)"] const CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM = 256 ; # [doc = "Camera supports tracking of a point on the camera view."] const CAMERA_CAP_FLAGS_HAS_TRACKING_POINT = 512 ; # [doc = "Camera supports tracking of a selection rectangle on the camera view."] const CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE = 1024 ; # [doc = "Camera supports tracking geo status (CAMERA_TRACKING_GEO_STATUS)."] const CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS = 2048 ; # [doc = "Camera supports absolute thermal range (request CAMERA_THERMAL_RANGE with MAV_CMD_REQUEST_MESSAGE)."] const CAMERA_CAP_FLAGS_HAS_THERMAL_RANGE = 4096 ; } }
413impl CameraCapFlags {
414 pub const DEFAULT: Self = Self::CAMERA_CAP_FLAGS_CAPTURE_VIDEO;
415}
416impl Default for CameraCapFlags {
417 fn default() -> Self {
418 Self::DEFAULT
419 }
420}
421#[cfg_attr(feature = "ts", derive(TS))]
422#[cfg_attr(feature = "ts", ts(export))]
423#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
424#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
425#[cfg_attr(feature = "serde", serde(tag = "type"))]
426#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
427#[repr(u32)]
428#[doc = "Camera Modes."]
429pub enum CameraMode {
430 #[doc = "Camera is in image/photo capture mode."]
431 CAMERA_MODE_IMAGE = 0,
432 #[doc = "Camera is in video capture mode."]
433 CAMERA_MODE_VIDEO = 1,
434 #[doc = "Camera is in image survey capture mode. It allows for camera controller to do specific settings for surveys."]
435 CAMERA_MODE_IMAGE_SURVEY = 2,
436}
437impl CameraMode {
438 pub const DEFAULT: Self = Self::CAMERA_MODE_IMAGE;
439}
440impl Default for CameraMode {
441 fn default() -> Self {
442 Self::DEFAULT
443 }
444}
445#[cfg_attr(feature = "ts", derive(TS))]
446#[cfg_attr(feature = "ts", ts(export))]
447#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
448#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
449#[cfg_attr(feature = "serde", serde(tag = "type"))]
450#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
451#[repr(u32)]
452#[doc = "Camera sources for MAV_CMD_SET_CAMERA_SOURCE"]
453pub enum CameraSource {
454 #[doc = "Default camera source."]
455 CAMERA_SOURCE_DEFAULT = 0,
456 #[doc = "RGB camera source."]
457 CAMERA_SOURCE_RGB = 1,
458 #[doc = "IR camera source."]
459 CAMERA_SOURCE_IR = 2,
460 #[doc = "NDVI camera source."]
461 CAMERA_SOURCE_NDVI = 3,
462}
463impl CameraSource {
464 pub const DEFAULT: Self = Self::CAMERA_SOURCE_DEFAULT;
465}
466impl Default for CameraSource {
467 fn default() -> Self {
468 Self::DEFAULT
469 }
470}
471#[cfg_attr(feature = "ts", derive(TS))]
472#[cfg_attr(feature = "ts", ts(export))]
473#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
474#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
475#[cfg_attr(feature = "serde", serde(tag = "type"))]
476#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
477#[repr(u32)]
478#[doc = "Camera tracking modes"]
479pub enum CameraTrackingMode {
480 #[doc = "Not tracking"]
481 CAMERA_TRACKING_MODE_NONE = 0,
482 #[doc = "Target is a point"]
483 CAMERA_TRACKING_MODE_POINT = 1,
484 #[doc = "Target is a rectangle"]
485 CAMERA_TRACKING_MODE_RECTANGLE = 2,
486}
487impl CameraTrackingMode {
488 pub const DEFAULT: Self = Self::CAMERA_TRACKING_MODE_NONE;
489}
490impl Default for CameraTrackingMode {
491 fn default() -> Self {
492 Self::DEFAULT
493 }
494}
495#[cfg_attr(feature = "ts", derive(TS))]
496#[cfg_attr(feature = "ts", ts(export))]
497#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
498#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
499#[cfg_attr(feature = "serde", serde(tag = "type"))]
500#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
501#[repr(u32)]
502#[doc = "Camera tracking status flags"]
503pub enum CameraTrackingStatusFlags {
504 #[doc = "Camera is not tracking"]
505 CAMERA_TRACKING_STATUS_FLAGS_IDLE = 0,
506 #[doc = "Camera is tracking"]
507 CAMERA_TRACKING_STATUS_FLAGS_ACTIVE = 1,
508 #[doc = "Camera tracking in error state"]
509 CAMERA_TRACKING_STATUS_FLAGS_ERROR = 2,
510}
511impl CameraTrackingStatusFlags {
512 pub const DEFAULT: Self = Self::CAMERA_TRACKING_STATUS_FLAGS_IDLE;
513}
514impl Default for CameraTrackingStatusFlags {
515 fn default() -> Self {
516 Self::DEFAULT
517 }
518}
519bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Camera tracking target data (shows where tracked target is within image)"] pub struct CameraTrackingTargetData : u8 { # [doc = "Target data embedded in image data (proprietary)"] const CAMERA_TRACKING_TARGET_DATA_EMBEDDED = 1 ; # [doc = "Target data rendered in image"] const CAMERA_TRACKING_TARGET_DATA_RENDERED = 2 ; # [doc = "Target data within status message (Point or Rectangle)"] const CAMERA_TRACKING_TARGET_DATA_IN_STATUS = 4 ; } }
520impl CameraTrackingTargetData {
521 pub const DEFAULT: Self = Self::CAMERA_TRACKING_TARGET_DATA_EMBEDDED;
522}
523impl Default for CameraTrackingTargetData {
524 fn default() -> Self {
525 Self::DEFAULT
526 }
527}
528#[cfg_attr(feature = "ts", derive(TS))]
529#[cfg_attr(feature = "ts", ts(export))]
530#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
531#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
532#[cfg_attr(feature = "serde", serde(tag = "type"))]
533#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
534#[repr(u32)]
535#[doc = "Zoom types for MAV_CMD_SET_CAMERA_ZOOM"]
536pub enum CameraZoomType {
537 #[doc = "Zoom one step increment (-1 for wide, 1 for tele)"]
538 ZOOM_TYPE_STEP = 0,
539 #[doc = "Continuous normalized zoom in/out rate until stopped. Range -1..1, negative: wide, positive: narrow/tele, 0 to stop zooming. Other values should be clipped to the range."]
540 ZOOM_TYPE_CONTINUOUS = 1,
541 #[doc = "Zoom value as proportion of full camera range (a percentage value between 0.0 and 100.0)"]
542 ZOOM_TYPE_RANGE = 2,
543 #[doc = "Zoom value/variable focal length in millimetres. Note that there is no message to get the valid zoom range of the camera, so this can type can only be used for cameras where the zoom range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera)"]
544 ZOOM_TYPE_FOCAL_LENGTH = 3,
545 #[doc = "Zoom value as horizontal field of view in degrees."]
546 ZOOM_TYPE_HORIZONTAL_FOV = 4,
547}
548impl CameraZoomType {
549 pub const DEFAULT: Self = Self::ZOOM_TYPE_STEP;
550}
551impl Default for CameraZoomType {
552 fn default() -> Self {
553 Self::DEFAULT
554 }
555}
556#[cfg_attr(feature = "ts", derive(TS))]
557#[cfg_attr(feature = "ts", ts(export))]
558#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
559#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
560#[cfg_attr(feature = "serde", serde(tag = "type"))]
561#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
562#[repr(u32)]
563pub enum CanFilterOp {
564 CAN_FILTER_REPLACE = 0,
565 CAN_FILTER_ADD = 1,
566 CAN_FILTER_REMOVE = 2,
567}
568impl CanFilterOp {
569 pub const DEFAULT: Self = Self::CAN_FILTER_REPLACE;
570}
571impl Default for CanFilterOp {
572 fn default() -> Self {
573 Self::DEFAULT
574 }
575}
576#[cfg_attr(feature = "ts", derive(TS))]
577#[cfg_attr(feature = "ts", ts(export))]
578#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
579#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
580#[cfg_attr(feature = "serde", serde(tag = "type"))]
581#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
582#[repr(u32)]
583#[doc = "Possible responses from a CELLULAR_CONFIG message."]
584pub enum CellularConfigResponse {
585 #[doc = "Changes accepted."]
586 CELLULAR_CONFIG_RESPONSE_ACCEPTED = 0,
587 #[doc = "Invalid APN."]
588 CELLULAR_CONFIG_RESPONSE_APN_ERROR = 1,
589 #[doc = "Invalid PIN."]
590 CELLULAR_CONFIG_RESPONSE_PIN_ERROR = 2,
591 #[doc = "Changes rejected."]
592 CELLULAR_CONFIG_RESPONSE_REJECTED = 3,
593 #[doc = "PUK is required to unblock SIM card."]
594 CELLULAR_CONFIG_BLOCKED_PUK_REQUIRED = 4,
595}
596impl CellularConfigResponse {
597 pub const DEFAULT: Self = Self::CELLULAR_CONFIG_RESPONSE_ACCEPTED;
598}
599impl Default for CellularConfigResponse {
600 fn default() -> Self {
601 Self::DEFAULT
602 }
603}
604#[cfg_attr(feature = "ts", derive(TS))]
605#[cfg_attr(feature = "ts", ts(export))]
606#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
607#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
608#[cfg_attr(feature = "serde", serde(tag = "type"))]
609#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
610#[repr(u32)]
611#[doc = "These flags are used to diagnose the failure state of CELLULAR_STATUS"]
612pub enum CellularNetworkFailedReason {
613 #[doc = "No error"]
614 CELLULAR_NETWORK_FAILED_REASON_NONE = 0,
615 #[doc = "Error state is unknown"]
616 CELLULAR_NETWORK_FAILED_REASON_UNKNOWN = 1,
617 #[doc = "SIM is required for the modem but missing"]
618 CELLULAR_NETWORK_FAILED_REASON_SIM_MISSING = 2,
619 #[doc = "SIM is available, but not usable for connection"]
620 CELLULAR_NETWORK_FAILED_REASON_SIM_ERROR = 3,
621}
622impl CellularNetworkFailedReason {
623 pub const DEFAULT: Self = Self::CELLULAR_NETWORK_FAILED_REASON_NONE;
624}
625impl Default for CellularNetworkFailedReason {
626 fn default() -> Self {
627 Self::DEFAULT
628 }
629}
630#[cfg_attr(feature = "ts", derive(TS))]
631#[cfg_attr(feature = "ts", ts(export))]
632#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
633#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
634#[cfg_attr(feature = "serde", serde(tag = "type"))]
635#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
636#[repr(u32)]
637#[doc = "Cellular network radio type"]
638pub enum CellularNetworkRadioType {
639 CELLULAR_NETWORK_RADIO_TYPE_NONE = 0,
640 CELLULAR_NETWORK_RADIO_TYPE_GSM = 1,
641 CELLULAR_NETWORK_RADIO_TYPE_CDMA = 2,
642 CELLULAR_NETWORK_RADIO_TYPE_WCDMA = 3,
643 CELLULAR_NETWORK_RADIO_TYPE_LTE = 4,
644}
645impl CellularNetworkRadioType {
646 pub const DEFAULT: Self = Self::CELLULAR_NETWORK_RADIO_TYPE_NONE;
647}
648impl Default for CellularNetworkRadioType {
649 fn default() -> Self {
650 Self::DEFAULT
651 }
652}
653#[cfg_attr(feature = "ts", derive(TS))]
654#[cfg_attr(feature = "ts", ts(export))]
655#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
656#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
657#[cfg_attr(feature = "serde", serde(tag = "type"))]
658#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
659#[repr(u32)]
660#[doc = "These flags encode the cellular network status"]
661pub enum CellularStatusFlag {
662 #[doc = "State unknown or not reportable."]
663 CELLULAR_STATUS_FLAG_UNKNOWN = 0,
664 #[doc = "Modem is unusable"]
665 CELLULAR_STATUS_FLAG_FAILED = 1,
666 #[doc = "Modem is being initialized"]
667 CELLULAR_STATUS_FLAG_INITIALIZING = 2,
668 #[doc = "Modem is locked"]
669 CELLULAR_STATUS_FLAG_LOCKED = 3,
670 #[doc = "Modem is not enabled and is powered down"]
671 CELLULAR_STATUS_FLAG_DISABLED = 4,
672 #[doc = "Modem is currently transitioning to the CELLULAR_STATUS_FLAG_DISABLED state"]
673 CELLULAR_STATUS_FLAG_DISABLING = 5,
674 #[doc = "Modem is currently transitioning to the CELLULAR_STATUS_FLAG_ENABLED state"]
675 CELLULAR_STATUS_FLAG_ENABLING = 6,
676 #[doc = "Modem is enabled and powered on but not registered with a network provider and not available for data connections"]
677 CELLULAR_STATUS_FLAG_ENABLED = 7,
678 #[doc = "Modem is searching for a network provider to register"]
679 CELLULAR_STATUS_FLAG_SEARCHING = 8,
680 #[doc = "Modem is registered with a network provider, and data connections and messaging may be available for use"]
681 CELLULAR_STATUS_FLAG_REGISTERED = 9,
682 #[doc = "Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated"]
683 CELLULAR_STATUS_FLAG_DISCONNECTING = 10,
684 #[doc = "Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered"]
685 CELLULAR_STATUS_FLAG_CONNECTING = 11,
686 #[doc = "One or more packet data bearers is active and connected"]
687 CELLULAR_STATUS_FLAG_CONNECTED = 12,
688}
689impl CellularStatusFlag {
690 pub const DEFAULT: Self = Self::CELLULAR_STATUS_FLAG_UNKNOWN;
691}
692impl Default for CellularStatusFlag {
693 fn default() -> Self {
694 Self::DEFAULT
695 }
696}
697#[cfg_attr(feature = "ts", derive(TS))]
698#[cfg_attr(feature = "ts", ts(export))]
699#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
700#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
701#[cfg_attr(feature = "serde", serde(tag = "type"))]
702#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
703#[repr(u32)]
704#[doc = "Supported component metadata types. These are used in the \"general\" metadata file returned by COMPONENT_METADATA to provide information about supported metadata types. The types are not used directly in MAVLink messages."]
705pub enum CompMetadataType {
706 #[doc = "General information about the component. General metadata includes information about other metadata types supported by the component. Files of this type must be supported, and must be downloadable from vehicle using a MAVLink FTP URI."]
707 COMP_METADATA_TYPE_GENERAL = 0,
708 #[doc = "Parameter meta data."]
709 COMP_METADATA_TYPE_PARAMETER = 1,
710 #[doc = "Meta data that specifies which commands and command parameters the vehicle supports. (WIP)"]
711 COMP_METADATA_TYPE_COMMANDS = 2,
712 #[doc = "Meta data that specifies external non-MAVLink peripherals."]
713 COMP_METADATA_TYPE_PERIPHERALS = 3,
714 #[doc = "Meta data for the events interface."]
715 COMP_METADATA_TYPE_EVENTS = 4,
716 #[doc = "Meta data for actuator configuration (motors, servos and vehicle geometry) and testing."]
717 COMP_METADATA_TYPE_ACTUATORS = 5,
718}
719impl CompMetadataType {
720 pub const DEFAULT: Self = Self::COMP_METADATA_TYPE_GENERAL;
721}
722impl Default for CompMetadataType {
723 fn default() -> Self {
724 Self::DEFAULT
725 }
726}
727#[cfg_attr(feature = "ts", derive(TS))]
728#[cfg_attr(feature = "ts", ts(export))]
729#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
730#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
731#[cfg_attr(feature = "serde", serde(tag = "type"))]
732#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
733#[repr(u32)]
734#[doc = "Indicates the ESC connection type."]
735pub enum EscConnectionType {
736 #[doc = "Traditional PPM ESC."]
737 ESC_CONNECTION_TYPE_PPM = 0,
738 #[doc = "Serial Bus connected ESC."]
739 ESC_CONNECTION_TYPE_SERIAL = 1,
740 #[doc = "One Shot PPM ESC."]
741 ESC_CONNECTION_TYPE_ONESHOT = 2,
742 #[doc = "I2C ESC."]
743 ESC_CONNECTION_TYPE_I2C = 3,
744 #[doc = "CAN-Bus ESC."]
745 ESC_CONNECTION_TYPE_CAN = 4,
746 #[doc = "DShot ESC."]
747 ESC_CONNECTION_TYPE_DSHOT = 5,
748}
749impl EscConnectionType {
750 pub const DEFAULT: Self = Self::ESC_CONNECTION_TYPE_PPM;
751}
752impl Default for EscConnectionType {
753 fn default() -> Self {
754 Self::DEFAULT
755 }
756}
757bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags to report ESC failures."] pub struct EscFailureFlags : u16 { # [doc = "Over current failure."] const ESC_FAILURE_OVER_CURRENT = 1 ; # [doc = "Over voltage failure."] const ESC_FAILURE_OVER_VOLTAGE = 2 ; # [doc = "Over temperature failure."] const ESC_FAILURE_OVER_TEMPERATURE = 4 ; # [doc = "Over RPM failure."] const ESC_FAILURE_OVER_RPM = 8 ; # [doc = "Inconsistent command failure i.e. out of bounds."] const ESC_FAILURE_INCONSISTENT_CMD = 16 ; # [doc = "Motor stuck failure."] const ESC_FAILURE_MOTOR_STUCK = 32 ; # [doc = "Generic ESC failure."] const ESC_FAILURE_GENERIC = 64 ; } }
758impl EscFailureFlags {
759 pub const DEFAULT: Self = Self::ESC_FAILURE_OVER_CURRENT;
760}
761impl Default for EscFailureFlags {
762 fn default() -> Self {
763 Self::DEFAULT
764 }
765}
766bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags in ESTIMATOR_STATUS message"] pub struct EstimatorStatusFlags : u16 { # [doc = "True if the attitude estimate is good"] const ESTIMATOR_ATTITUDE = 1 ; # [doc = "True if the horizontal velocity estimate is good"] const ESTIMATOR_VELOCITY_HORIZ = 2 ; # [doc = "True if the vertical velocity estimate is good"] const ESTIMATOR_VELOCITY_VERT = 4 ; # [doc = "True if the horizontal position (relative) estimate is good"] const ESTIMATOR_POS_HORIZ_REL = 8 ; # [doc = "True if the horizontal position (absolute) estimate is good"] const ESTIMATOR_POS_HORIZ_ABS = 16 ; # [doc = "True if the vertical position (absolute) estimate is good"] const ESTIMATOR_POS_VERT_ABS = 32 ; # [doc = "True if the vertical position (above ground) estimate is good"] const ESTIMATOR_POS_VERT_AGL = 64 ; # [doc = "True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow)"] const ESTIMATOR_CONST_POS_MODE = 128 ; # [doc = "True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate"] const ESTIMATOR_PRED_POS_HORIZ_REL = 256 ; # [doc = "True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate"] const ESTIMATOR_PRED_POS_HORIZ_ABS = 512 ; # [doc = "True if the EKF has detected a GPS glitch"] const ESTIMATOR_GPS_GLITCH = 1024 ; # [doc = "True if the EKF has detected bad accelerometer data"] const ESTIMATOR_ACCEL_ERROR = 2048 ; } }
767impl EstimatorStatusFlags {
768 pub const DEFAULT: Self = Self::ESTIMATOR_ATTITUDE;
769}
770impl Default for EstimatorStatusFlags {
771 fn default() -> Self {
772 Self::DEFAULT
773 }
774}
775#[cfg_attr(feature = "ts", derive(TS))]
776#[cfg_attr(feature = "ts", ts(export))]
777#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
778#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
779#[cfg_attr(feature = "serde", serde(tag = "type"))]
780#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
781#[repr(u32)]
782#[doc = "List of possible failure type to inject."]
783pub enum FailureType {
784 #[doc = "No failure injected, used to reset a previous failure."]
785 FAILURE_TYPE_OK = 0,
786 #[doc = "Sets unit off, so completely non-responsive."]
787 FAILURE_TYPE_OFF = 1,
788 #[doc = "Unit is stuck e.g. keeps reporting the same value."]
789 FAILURE_TYPE_STUCK = 2,
790 #[doc = "Unit is reporting complete garbage."]
791 FAILURE_TYPE_GARBAGE = 3,
792 #[doc = "Unit is consistently wrong."]
793 FAILURE_TYPE_WRONG = 4,
794 #[doc = "Unit is slow, so e.g. reporting at slower than expected rate."]
795 FAILURE_TYPE_SLOW = 5,
796 #[doc = "Data of unit is delayed in time."]
797 FAILURE_TYPE_DELAYED = 6,
798 #[doc = "Unit is sometimes working, sometimes not."]
799 FAILURE_TYPE_INTERMITTENT = 7,
800}
801impl FailureType {
802 pub const DEFAULT: Self = Self::FAILURE_TYPE_OK;
803}
804impl Default for FailureType {
805 fn default() -> Self {
806 Self::DEFAULT
807 }
808}
809#[cfg_attr(feature = "ts", derive(TS))]
810#[cfg_attr(feature = "ts", ts(export))]
811#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
812#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
813#[cfg_attr(feature = "serde", serde(tag = "type"))]
814#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
815#[repr(u32)]
816#[doc = "List of possible units where failures can be injected."]
817pub enum FailureUnit {
818 FAILURE_UNIT_SENSOR_GYRO = 0,
819 FAILURE_UNIT_SENSOR_ACCEL = 1,
820 FAILURE_UNIT_SENSOR_MAG = 2,
821 FAILURE_UNIT_SENSOR_BARO = 3,
822 FAILURE_UNIT_SENSOR_GPS = 4,
823 FAILURE_UNIT_SENSOR_OPTICAL_FLOW = 5,
824 FAILURE_UNIT_SENSOR_VIO = 6,
825 FAILURE_UNIT_SENSOR_DISTANCE_SENSOR = 7,
826 FAILURE_UNIT_SENSOR_AIRSPEED = 8,
827 FAILURE_UNIT_SYSTEM_BATTERY = 100,
828 FAILURE_UNIT_SYSTEM_MOTOR = 101,
829 FAILURE_UNIT_SYSTEM_SERVO = 102,
830 FAILURE_UNIT_SYSTEM_AVOIDANCE = 103,
831 FAILURE_UNIT_SYSTEM_RC_SIGNAL = 104,
832 FAILURE_UNIT_SYSTEM_MAVLINK_SIGNAL = 105,
833}
834impl FailureUnit {
835 pub const DEFAULT: Self = Self::FAILURE_UNIT_SENSOR_GYRO;
836}
837impl Default for FailureUnit {
838 fn default() -> Self {
839 Self::DEFAULT
840 }
841}
842#[cfg_attr(feature = "ts", derive(TS))]
843#[cfg_attr(feature = "ts", ts(export))]
844#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
845#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
846#[cfg_attr(feature = "serde", serde(tag = "type"))]
847#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
848#[repr(u32)]
849pub enum FenceBreach {
850 #[doc = "No last fence breach"]
851 FENCE_BREACH_NONE = 0,
852 #[doc = "Breached minimum altitude"]
853 FENCE_BREACH_MINALT = 1,
854 #[doc = "Breached maximum altitude"]
855 FENCE_BREACH_MAXALT = 2,
856 #[doc = "Breached fence boundary"]
857 FENCE_BREACH_BOUNDARY = 3,
858}
859impl FenceBreach {
860 pub const DEFAULT: Self = Self::FENCE_BREACH_NONE;
861}
862impl Default for FenceBreach {
863 fn default() -> Self {
864 Self::DEFAULT
865 }
866}
867#[cfg_attr(feature = "ts", derive(TS))]
868#[cfg_attr(feature = "ts", ts(export))]
869#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
870#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
871#[cfg_attr(feature = "serde", serde(tag = "type"))]
872#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
873#[repr(u32)]
874#[doc = "Actions being taken to mitigate/prevent fence breach"]
875pub enum FenceMitigate {
876 #[doc = "Unknown"]
877 FENCE_MITIGATE_UNKNOWN = 0,
878 #[doc = "No actions being taken"]
879 FENCE_MITIGATE_NONE = 1,
880 #[doc = "Velocity limiting active to prevent breach"]
881 FENCE_MITIGATE_VEL_LIMIT = 2,
882}
883impl FenceMitigate {
884 pub const DEFAULT: Self = Self::FENCE_MITIGATE_UNKNOWN;
885}
886impl Default for FenceMitigate {
887 fn default() -> Self {
888 Self::DEFAULT
889 }
890}
891#[cfg_attr(feature = "ts", derive(TS))]
892#[cfg_attr(feature = "ts", ts(export))]
893#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
894#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
895#[cfg_attr(feature = "serde", serde(tag = "type"))]
896#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
897#[repr(u32)]
898#[doc = "Fence types to enable or disable when using MAV_CMD_DO_FENCE_ENABLE. Note that at least one of these flags must be set in MAV_CMD_DO_FENCE_ENABLE.param2. If none are set, the flight stack will ignore the field and enable/disable its default set of fences (usually all of them)."]
899pub enum FenceType {
900 #[doc = "Maximum altitude fence"]
901 FENCE_TYPE_ALT_MAX = 1,
902 #[doc = "Circle fence"]
903 FENCE_TYPE_CIRCLE = 2,
904 #[doc = "Polygon fence"]
905 FENCE_TYPE_POLYGON = 4,
906 #[doc = "Minimum altitude fence"]
907 FENCE_TYPE_ALT_MIN = 8,
908}
909impl FenceType {
910 pub const DEFAULT: Self = Self::FENCE_TYPE_ALT_MAX;
911}
912impl Default for FenceType {
913 fn default() -> Self {
914 Self::DEFAULT
915 }
916}
917#[cfg_attr(feature = "ts", derive(TS))]
918#[cfg_attr(feature = "ts", ts(export))]
919#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
920#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
921#[cfg_attr(feature = "serde", serde(tag = "type"))]
922#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
923#[repr(u32)]
924#[doc = "These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65."]
925pub enum FirmwareVersionType {
926 #[doc = "development release"]
927 FIRMWARE_VERSION_TYPE_DEV = 0,
928 #[doc = "alpha release"]
929 FIRMWARE_VERSION_TYPE_ALPHA = 64,
930 #[doc = "beta release"]
931 FIRMWARE_VERSION_TYPE_BETA = 128,
932 #[doc = "release candidate"]
933 FIRMWARE_VERSION_TYPE_RC = 192,
934 #[doc = "official stable release"]
935 FIRMWARE_VERSION_TYPE_OFFICIAL = 255,
936}
937impl FirmwareVersionType {
938 pub const DEFAULT: Self = Self::FIRMWARE_VERSION_TYPE_DEV;
939}
940impl Default for FirmwareVersionType {
941 fn default() -> Self {
942 Self::DEFAULT
943 }
944}
945bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Gimbal device (low level) capability flags (bitmap)."] pub struct GimbalDeviceCapFlags : u16 { # [doc = "Gimbal device supports a retracted position."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT = 1 ; # [doc = "Gimbal device supports a horizontal, forward looking position, stabilized."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL = 2 ; # [doc = "Gimbal device supports rotating around roll axis."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS = 4 ; # [doc = "Gimbal device supports to follow a roll angle relative to the vehicle."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW = 8 ; # [doc = "Gimbal device supports locking to a roll angle (generally that's the default with roll stabilized)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK = 16 ; # [doc = "Gimbal device supports rotating around pitch axis."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS = 32 ; # [doc = "Gimbal device supports to follow a pitch angle relative to the vehicle."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW = 64 ; # [doc = "Gimbal device supports locking to a pitch angle (generally that's the default with pitch stabilized)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK = 128 ; # [doc = "Gimbal device supports rotating around yaw axis."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS = 256 ; # [doc = "Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW = 512 ; # [doc = "Gimbal device supports locking to an absolute heading, i.e., yaw angle relative to North (earth frame, often this is an option available)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK = 1024 ; # [doc = "Gimbal device supports yawing/panning infinitely (e.g. using slip disk)."] const GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW = 2048 ; # [doc = "Gimbal device supports yaw angles and angular velocities relative to North (earth frame). This usually requires support by an autopilot via AUTOPILOT_STATE_FOR_GIMBAL_DEVICE. Support can go on and off during runtime, which is reported by the flag GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_IN_EARTH_FRAME."] const GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME = 4096 ; # [doc = "Gimbal device supports radio control inputs as an alternative input for controlling the gimbal orientation."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS = 8192 ; } }
946impl GimbalDeviceCapFlags {
947 pub const DEFAULT: Self = Self::GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT;
948}
949impl Default for GimbalDeviceCapFlags {
950 fn default() -> Self {
951 Self::DEFAULT
952 }
953}
954bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Gimbal device (low level) error flags (bitmap, 0 means no error)"] pub struct GimbalDeviceErrorFlags : u32 { # [doc = "Gimbal device is limited by hardware roll limit."] const GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT = 1 ; # [doc = "Gimbal device is limited by hardware pitch limit."] const GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT = 2 ; # [doc = "Gimbal device is limited by hardware yaw limit."] const GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT = 4 ; # [doc = "There is an error with the gimbal encoders."] const GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR = 8 ; # [doc = "There is an error with the gimbal power source."] const GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR = 16 ; # [doc = "There is an error with the gimbal motors."] const GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR = 32 ; # [doc = "There is an error with the gimbal's software."] const GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR = 64 ; # [doc = "There is an error with the gimbal's communication."] const GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR = 128 ; # [doc = "Gimbal device is currently calibrating."] const GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING = 256 ; # [doc = "Gimbal device is not assigned to a gimbal manager."] const GIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER = 512 ; } }
955impl GimbalDeviceErrorFlags {
956 pub const DEFAULT: Self = Self::GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT;
957}
958impl Default for GimbalDeviceErrorFlags {
959 fn default() -> Self {
960 Self::DEFAULT
961 }
962}
963bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags for gimbal device (lower level) operation."] pub struct GimbalDeviceFlags : u16 { # [doc = "Set to retracted safe position (no stabilization), takes precedence over all other flags."] const GIMBAL_DEVICE_FLAGS_RETRACT = 1 ; # [doc = "Set to neutral/default position, taking precedence over all other flags except RETRACT. Neutral is commonly forward-facing and horizontal (roll=pitch=yaw=0) but may be any orientation."] const GIMBAL_DEVICE_FLAGS_NEUTRAL = 2 ; # [doc = "Lock roll angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal."] const GIMBAL_DEVICE_FLAGS_ROLL_LOCK = 4 ; # [doc = "Lock pitch angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal."] const GIMBAL_DEVICE_FLAGS_PITCH_LOCK = 8 ; # [doc = "Lock yaw angle to absolute angle relative to North (not relative to vehicle). If this flag is set, the yaw angle and z component of angular velocity are relative to North (earth frame, x-axis pointing North), else they are relative to the vehicle heading (vehicle frame, earth frame rotated so that the x-axis is pointing forward)."] const GIMBAL_DEVICE_FLAGS_YAW_LOCK = 16 ; # [doc = "Yaw angle and z component of angular velocity are relative to the vehicle heading (vehicle frame, earth frame rotated such that the x-axis is pointing forward)."] const GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME = 32 ; # [doc = "Yaw angle and z component of angular velocity are relative to North (earth frame, x-axis is pointing North)."] const GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME = 64 ; # [doc = "Gimbal device can accept yaw angle inputs relative to North (earth frame). This flag is only for reporting (attempts to set this flag are ignored)."] const GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = 128 ; # [doc = "The gimbal orientation is set exclusively by the RC signals feed to the gimbal's radio control inputs. MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE) are ignored."] const GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE = 256 ; # [doc = "The gimbal orientation is determined by combining/mixing the RC signals feed to the gimbal's radio control inputs and the MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE). How these two controls are combined or mixed is not defined by the protocol but is up to the implementation."] const GIMBAL_DEVICE_FLAGS_RC_MIXED = 512 ; } }
964impl GimbalDeviceFlags {
965 pub const DEFAULT: Self = Self::GIMBAL_DEVICE_FLAGS_RETRACT;
966}
967impl Default for GimbalDeviceFlags {
968 fn default() -> Self {
969 Self::DEFAULT
970 }
971}
972bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Gimbal manager high level capability flags (bitmap). The first 16 bits are identical to the GIMBAL_DEVICE_CAP_FLAGS. However, the gimbal manager does not need to copy the flags from the gimbal but can also enhance the capabilities and thus add flags."] pub struct GimbalManagerCapFlags : u32 { # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT = 1 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_NEUTRAL = 2 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_AXIS = 4 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_FOLLOW = 8 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_LOCK = 16 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_AXIS = 32 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_FOLLOW = 64 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_LOCK = 128 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_AXIS = 256 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_FOLLOW = 512 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_LOCK = 1024 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW."] const GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_INFINITE_YAW = 2048 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME."] const GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME = 4096 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_RC_INPUTS = 8192 ; # [doc = "Gimbal manager supports to point to a local position."] const GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_LOCAL = 65536 ; # [doc = "Gimbal manager supports to point to a global latitude, longitude, altitude position."] const GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL = 131072 ; } }
973impl GimbalManagerCapFlags {
974 pub const DEFAULT: Self = Self::GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT;
975}
976impl Default for GimbalManagerCapFlags {
977 fn default() -> Self {
978 Self::DEFAULT
979 }
980}
981bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags for high level gimbal manager operation The first 16 bits are identical to the GIMBAL_DEVICE_FLAGS."] pub struct GimbalManagerFlags : u32 { # [doc = "Based on GIMBAL_DEVICE_FLAGS_RETRACT."] const GIMBAL_MANAGER_FLAGS_RETRACT = 1 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_NEUTRAL."] const GIMBAL_MANAGER_FLAGS_NEUTRAL = 2 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_ROLL_LOCK."] const GIMBAL_MANAGER_FLAGS_ROLL_LOCK = 4 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_PITCH_LOCK."] const GIMBAL_MANAGER_FLAGS_PITCH_LOCK = 8 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_YAW_LOCK."] const GIMBAL_MANAGER_FLAGS_YAW_LOCK = 16 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME."] const GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME = 32 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME."] const GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME = 64 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME."] const GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = 128 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE."] const GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE = 256 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_RC_MIXED."] const GIMBAL_MANAGER_FLAGS_RC_MIXED = 512 ; } }
982impl GimbalManagerFlags {
983 pub const DEFAULT: Self = Self::GIMBAL_MANAGER_FLAGS_RETRACT;
984}
985impl Default for GimbalManagerFlags {
986 fn default() -> Self {
987 Self::DEFAULT
988 }
989}
990#[cfg_attr(feature = "ts", derive(TS))]
991#[cfg_attr(feature = "ts", ts(export))]
992#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
993#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
994#[cfg_attr(feature = "serde", serde(tag = "type"))]
995#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
996#[repr(u32)]
997#[doc = "Type of GPS fix"]
998pub enum GpsFixType {
999 #[doc = "No GPS connected"]
1000 GPS_FIX_TYPE_NO_GPS = 0,
1001 #[doc = "No position information, GPS is connected"]
1002 GPS_FIX_TYPE_NO_FIX = 1,
1003 #[doc = "2D position"]
1004 GPS_FIX_TYPE_2D_FIX = 2,
1005 #[doc = "3D position"]
1006 GPS_FIX_TYPE_3D_FIX = 3,
1007 #[doc = "DGPS/SBAS aided 3D position"]
1008 GPS_FIX_TYPE_DGPS = 4,
1009 #[doc = "RTK float, 3D position"]
1010 GPS_FIX_TYPE_RTK_FLOAT = 5,
1011 #[doc = "RTK Fixed, 3D position"]
1012 GPS_FIX_TYPE_RTK_FIXED = 6,
1013 #[doc = "Static fixed, typically used for base stations"]
1014 GPS_FIX_TYPE_STATIC = 7,
1015 #[doc = "PPP, 3D position."]
1016 GPS_FIX_TYPE_PPP = 8,
1017}
1018impl GpsFixType {
1019 pub const DEFAULT: Self = Self::GPS_FIX_TYPE_NO_GPS;
1020}
1021impl Default for GpsFixType {
1022 fn default() -> Self {
1023 Self::DEFAULT
1024 }
1025}
1026bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] pub struct GpsInputIgnoreFlags : u16 { # [doc = "ignore altitude field"] const GPS_INPUT_IGNORE_FLAG_ALT = 1 ; # [doc = "ignore hdop field"] const GPS_INPUT_IGNORE_FLAG_HDOP = 2 ; # [doc = "ignore vdop field"] const GPS_INPUT_IGNORE_FLAG_VDOP = 4 ; # [doc = "ignore horizontal velocity field (vn and ve)"] const GPS_INPUT_IGNORE_FLAG_VEL_HORIZ = 8 ; # [doc = "ignore vertical velocity field (vd)"] const GPS_INPUT_IGNORE_FLAG_VEL_VERT = 16 ; # [doc = "ignore speed accuracy field"] const GPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY = 32 ; # [doc = "ignore horizontal accuracy field"] const GPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACY = 64 ; # [doc = "ignore vertical accuracy field"] const GPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACY = 128 ; } }
1027impl GpsInputIgnoreFlags {
1028 pub const DEFAULT: Self = Self::GPS_INPUT_IGNORE_FLAG_ALT;
1029}
1030impl Default for GpsInputIgnoreFlags {
1031 fn default() -> Self {
1032 Self::DEFAULT
1033 }
1034}
1035#[cfg_attr(feature = "ts", derive(TS))]
1036#[cfg_attr(feature = "ts", ts(export))]
1037#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1038#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1039#[cfg_attr(feature = "serde", serde(tag = "type"))]
1040#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1041#[repr(u32)]
1042#[doc = "Gripper actions."]
1043pub enum GripperActions {
1044 #[doc = "Gripper release cargo."]
1045 GRIPPER_ACTION_RELEASE = 0,
1046 #[doc = "Gripper grab onto cargo."]
1047 GRIPPER_ACTION_GRAB = 1,
1048}
1049impl GripperActions {
1050 pub const DEFAULT: Self = Self::GRIPPER_ACTION_RELEASE;
1051}
1052impl Default for GripperActions {
1053 fn default() -> Self {
1054 Self::DEFAULT
1055 }
1056}
1057bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags in the HIGHRES_IMU message indicate which fields have updated since the last message"] pub struct HighresImuUpdatedFlags : u16 { # [doc = "The value in the xacc field has been updated"] const HIGHRES_IMU_UPDATED_XACC = 1 ; # [doc = "The value in the yacc field has been updated"] const HIGHRES_IMU_UPDATED_YACC = 2 ; # [doc = "The value in the zacc field has been updated since"] const HIGHRES_IMU_UPDATED_ZACC = 4 ; # [doc = "The value in the xgyro field has been updated"] const HIGHRES_IMU_UPDATED_XGYRO = 8 ; # [doc = "The value in the ygyro field has been updated"] const HIGHRES_IMU_UPDATED_YGYRO = 16 ; # [doc = "The value in the zgyro field has been updated"] const HIGHRES_IMU_UPDATED_ZGYRO = 32 ; # [doc = "The value in the xmag field has been updated"] const HIGHRES_IMU_UPDATED_XMAG = 64 ; # [doc = "The value in the ymag field has been updated"] const HIGHRES_IMU_UPDATED_YMAG = 128 ; # [doc = "The value in the zmag field has been updated"] const HIGHRES_IMU_UPDATED_ZMAG = 256 ; # [doc = "The value in the abs_pressure field has been updated"] const HIGHRES_IMU_UPDATED_ABS_PRESSURE = 512 ; # [doc = "The value in the diff_pressure field has been updated"] const HIGHRES_IMU_UPDATED_DIFF_PRESSURE = 1024 ; # [doc = "The value in the pressure_alt field has been updated"] const HIGHRES_IMU_UPDATED_PRESSURE_ALT = 2048 ; # [doc = "The value in the temperature field has been updated"] const HIGHRES_IMU_UPDATED_TEMPERATURE = 4096 ; } }
1058impl HighresImuUpdatedFlags {
1059 pub const DEFAULT: Self = Self::HIGHRES_IMU_UPDATED_XACC;
1060}
1061impl Default for HighresImuUpdatedFlags {
1062 fn default() -> Self {
1063 Self::DEFAULT
1064 }
1065}
1066bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags used in HIL_ACTUATOR_CONTROLS message."] pub struct HilActuatorControlsFlags : u64 { # [doc = "Simulation is using lockstep"] const HIL_ACTUATOR_CONTROLS_FLAGS_LOCKSTEP = 1 ; } }
1067impl HilActuatorControlsFlags {
1068 pub const DEFAULT: Self = Self::HIL_ACTUATOR_CONTROLS_FLAGS_LOCKSTEP;
1069}
1070impl Default for HilActuatorControlsFlags {
1071 fn default() -> Self {
1072 Self::DEFAULT
1073 }
1074}
1075bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags in the HIL_SENSOR message indicate which fields have updated since the last message"] pub struct HilSensorUpdatedFlags : u32 { # [doc = "The value in the xacc field has been updated"] const HIL_SENSOR_UPDATED_XACC = 1 ; # [doc = "The value in the yacc field has been updated"] const HIL_SENSOR_UPDATED_YACC = 2 ; # [doc = "The value in the zacc field has been updated"] const HIL_SENSOR_UPDATED_ZACC = 4 ; # [doc = "The value in the xgyro field has been updated"] const HIL_SENSOR_UPDATED_XGYRO = 8 ; # [doc = "The value in the ygyro field has been updated"] const HIL_SENSOR_UPDATED_YGYRO = 16 ; # [doc = "The value in the zgyro field has been updated"] const HIL_SENSOR_UPDATED_ZGYRO = 32 ; # [doc = "The value in the xmag field has been updated"] const HIL_SENSOR_UPDATED_XMAG = 64 ; # [doc = "The value in the ymag field has been updated"] const HIL_SENSOR_UPDATED_YMAG = 128 ; # [doc = "The value in the zmag field has been updated"] const HIL_SENSOR_UPDATED_ZMAG = 256 ; # [doc = "The value in the abs_pressure field has been updated"] const HIL_SENSOR_UPDATED_ABS_PRESSURE = 512 ; # [doc = "The value in the diff_pressure field has been updated"] const HIL_SENSOR_UPDATED_DIFF_PRESSURE = 1024 ; # [doc = "The value in the pressure_alt field has been updated"] const HIL_SENSOR_UPDATED_PRESSURE_ALT = 2048 ; # [doc = "The value in the temperature field has been updated"] const HIL_SENSOR_UPDATED_TEMPERATURE = 4096 ; # [doc = "Full reset of attitude/position/velocities/etc was performed in sim (Bit 31)."] const HIL_SENSOR_UPDATED_RESET = 2147483648 ; } }
1076impl HilSensorUpdatedFlags {
1077 pub const DEFAULT: Self = Self::HIL_SENSOR_UPDATED_XACC;
1078}
1079impl Default for HilSensorUpdatedFlags {
1080 fn default() -> Self {
1081 Self::DEFAULT
1082 }
1083}
1084bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags to report failure cases over the high latency telemetry."] pub struct HlFailureFlag : u16 { # [doc = "GPS failure."] const HL_FAILURE_FLAG_GPS = 1 ; # [doc = "Differential pressure sensor failure."] const HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE = 2 ; # [doc = "Absolute pressure sensor failure."] const HL_FAILURE_FLAG_ABSOLUTE_PRESSURE = 4 ; # [doc = "Accelerometer sensor failure."] const HL_FAILURE_FLAG_3D_ACCEL = 8 ; # [doc = "Gyroscope sensor failure."] const HL_FAILURE_FLAG_3D_GYRO = 16 ; # [doc = "Magnetometer sensor failure."] const HL_FAILURE_FLAG_3D_MAG = 32 ; # [doc = "Terrain subsystem failure."] const HL_FAILURE_FLAG_TERRAIN = 64 ; # [doc = "Battery failure/critical low battery."] const HL_FAILURE_FLAG_BATTERY = 128 ; # [doc = "RC receiver failure/no RC connection."] const HL_FAILURE_FLAG_RC_RECEIVER = 256 ; # [doc = "Offboard link failure."] const HL_FAILURE_FLAG_OFFBOARD_LINK = 512 ; # [doc = "Engine failure."] const HL_FAILURE_FLAG_ENGINE = 1024 ; # [doc = "Geofence violation."] const HL_FAILURE_FLAG_GEOFENCE = 2048 ; # [doc = "Estimator failure, for example measurement rejection or large variances."] const HL_FAILURE_FLAG_ESTIMATOR = 4096 ; # [doc = "Mission failure."] const HL_FAILURE_FLAG_MISSION = 8192 ; } }
1085impl HlFailureFlag {
1086 pub const DEFAULT: Self = Self::HL_FAILURE_FLAG_GPS;
1087}
1088impl Default for HlFailureFlag {
1089 fn default() -> Self {
1090 Self::DEFAULT
1091 }
1092}
1093bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Illuminator module error flags (bitmap, 0 means no error)"] pub struct IlluminatorErrorFlags : u32 { # [doc = "Illuminator thermal throttling error."] const ILLUMINATOR_ERROR_FLAGS_THERMAL_THROTTLING = 1 ; # [doc = "Illuminator over temperature shutdown error."] const ILLUMINATOR_ERROR_FLAGS_OVER_TEMPERATURE_SHUTDOWN = 2 ; # [doc = "Illuminator thermistor failure."] const ILLUMINATOR_ERROR_FLAGS_THERMISTOR_FAILURE = 4 ; } }
1094impl IlluminatorErrorFlags {
1095 pub const DEFAULT: Self = Self::ILLUMINATOR_ERROR_FLAGS_THERMAL_THROTTLING;
1096}
1097impl Default for IlluminatorErrorFlags {
1098 fn default() -> Self {
1099 Self::DEFAULT
1100 }
1101}
1102#[cfg_attr(feature = "ts", derive(TS))]
1103#[cfg_attr(feature = "ts", ts(export))]
1104#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1105#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1106#[cfg_attr(feature = "serde", serde(tag = "type"))]
1107#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1108#[repr(u32)]
1109#[doc = "Modes of illuminator"]
1110pub enum IlluminatorMode {
1111 #[doc = "Illuminator mode is not specified/unknown"]
1112 ILLUMINATOR_MODE_UNKNOWN = 0,
1113 #[doc = "Illuminator behavior is controlled by MAV_CMD_DO_ILLUMINATOR_CONFIGURE settings"]
1114 ILLUMINATOR_MODE_INTERNAL_CONTROL = 1,
1115 #[doc = "Illuminator behavior is controlled by external factors: e.g. an external hardware signal"]
1116 ILLUMINATOR_MODE_EXTERNAL_SYNC = 2,
1117}
1118impl IlluminatorMode {
1119 pub const DEFAULT: Self = Self::ILLUMINATOR_MODE_UNKNOWN;
1120}
1121impl Default for IlluminatorMode {
1122 fn default() -> Self {
1123 Self::DEFAULT
1124 }
1125}
1126#[cfg_attr(feature = "ts", derive(TS))]
1127#[cfg_attr(feature = "ts", ts(export))]
1128#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1129#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1130#[cfg_attr(feature = "serde", serde(tag = "type"))]
1131#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1132#[repr(u32)]
1133#[doc = "Type of landing target"]
1134pub enum LandingTargetType {
1135 #[doc = "Landing target signaled by light beacon (ex: IR-LOCK)"]
1136 LANDING_TARGET_TYPE_LIGHT_BEACON = 0,
1137 #[doc = "Landing target signaled by radio beacon (ex: ILS, NDB)"]
1138 LANDING_TARGET_TYPE_RADIO_BEACON = 1,
1139 #[doc = "Landing target represented by a fiducial marker (ex: ARTag)"]
1140 LANDING_TARGET_TYPE_VISION_FIDUCIAL = 2,
1141 #[doc = "Landing target represented by a pre-defined visual shape/feature (ex: X-marker, H-marker, square)"]
1142 LANDING_TARGET_TYPE_VISION_OTHER = 3,
1143}
1144impl LandingTargetType {
1145 pub const DEFAULT: Self = Self::LANDING_TARGET_TYPE_LIGHT_BEACON;
1146}
1147impl Default for LandingTargetType {
1148 fn default() -> Self {
1149 Self::DEFAULT
1150 }
1151}
1152#[cfg_attr(feature = "ts", derive(TS))]
1153#[cfg_attr(feature = "ts", ts(export))]
1154#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1155#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1156#[cfg_attr(feature = "serde", serde(tag = "type"))]
1157#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1158#[repr(u32)]
1159pub enum MagCalStatus {
1160 MAG_CAL_NOT_STARTED = 0,
1161 MAG_CAL_WAITING_TO_START = 1,
1162 MAG_CAL_RUNNING_STEP_ONE = 2,
1163 MAG_CAL_RUNNING_STEP_TWO = 3,
1164 MAG_CAL_SUCCESS = 4,
1165 MAG_CAL_FAILED = 5,
1166 MAG_CAL_BAD_ORIENTATION = 6,
1167 MAG_CAL_BAD_RADIUS = 7,
1168}
1169impl MagCalStatus {
1170 pub const DEFAULT: Self = Self::MAG_CAL_NOT_STARTED;
1171}
1172impl Default for MagCalStatus {
1173 fn default() -> Self {
1174 Self::DEFAULT
1175 }
1176}
1177#[cfg_attr(feature = "ts", derive(TS))]
1178#[cfg_attr(feature = "ts", ts(export))]
1179#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1180#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1181#[cfg_attr(feature = "serde", serde(tag = "type"))]
1182#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1183#[repr(u32)]
1184pub enum MavArmAuthDeniedReason {
1185 #[doc = "Not a specific reason"]
1186 MAV_ARM_AUTH_DENIED_REASON_GENERIC = 0,
1187 #[doc = "Authorizer will send the error as string to GCS"]
1188 MAV_ARM_AUTH_DENIED_REASON_NONE = 1,
1189 #[doc = "At least one waypoint have a invalid value"]
1190 MAV_ARM_AUTH_DENIED_REASON_INVALID_WAYPOINT = 2,
1191 #[doc = "Timeout in the authorizer process(in case it depends on network)"]
1192 MAV_ARM_AUTH_DENIED_REASON_TIMEOUT = 3,
1193 #[doc = "Airspace of the mission in use by another vehicle, second result parameter can have the waypoint id that caused it to be denied."]
1194 MAV_ARM_AUTH_DENIED_REASON_AIRSPACE_IN_USE = 4,
1195 #[doc = "Weather is not good to fly"]
1196 MAV_ARM_AUTH_DENIED_REASON_BAD_WEATHER = 5,
1197}
1198impl MavArmAuthDeniedReason {
1199 pub const DEFAULT: Self = Self::MAV_ARM_AUTH_DENIED_REASON_GENERIC;
1200}
1201impl Default for MavArmAuthDeniedReason {
1202 fn default() -> Self {
1203 Self::DEFAULT
1204 }
1205}
1206#[cfg_attr(feature = "ts", derive(TS))]
1207#[cfg_attr(feature = "ts", ts(export))]
1208#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1209#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1210#[cfg_attr(feature = "serde", serde(tag = "type"))]
1211#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1212#[repr(u32)]
1213#[doc = "Micro air vehicle / autopilot classes. This identifies the individual model."]
1214pub enum MavAutopilot {
1215 #[doc = "Generic autopilot, full support for everything"]
1216 MAV_AUTOPILOT_GENERIC = 0,
1217 #[doc = "Reserved for future use."]
1218 MAV_AUTOPILOT_RESERVED = 1,
1219 #[doc = "SLUGS autopilot, <http://slugsuav.soe.ucsc.edu>"]
1220 MAV_AUTOPILOT_SLUGS = 2,
1221 #[doc = "ArduPilot - Plane/Copter/Rover/Sub/Tracker, <https://ardupilot.org>"]
1222 MAV_AUTOPILOT_ARDUPILOTMEGA = 3,
1223 #[doc = "OpenPilot, <http://openpilot.org>"]
1224 MAV_AUTOPILOT_OPENPILOT = 4,
1225 #[doc = "Generic autopilot only supporting simple waypoints"]
1226 MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY = 5,
1227 #[doc = "Generic autopilot supporting waypoints and other simple navigation commands"]
1228 MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY = 6,
1229 #[doc = "Generic autopilot supporting the full mission command set"]
1230 MAV_AUTOPILOT_GENERIC_MISSION_FULL = 7,
1231 #[doc = "No valid autopilot, e.g. a GCS or other MAVLink component"]
1232 MAV_AUTOPILOT_INVALID = 8,
1233 #[doc = "PPZ UAV - <http://nongnu.org/paparazzi>"]
1234 MAV_AUTOPILOT_PPZ = 9,
1235 #[doc = "UAV Dev Board"]
1236 MAV_AUTOPILOT_UDB = 10,
1237 #[doc = "FlexiPilot"]
1238 MAV_AUTOPILOT_FP = 11,
1239 #[doc = "PX4 Autopilot - <http://px4.io/>"]
1240 MAV_AUTOPILOT_PX4 = 12,
1241 #[doc = "SMACCMPilot - <http://smaccmpilot.org>"]
1242 MAV_AUTOPILOT_SMACCMPILOT = 13,
1243 #[doc = "AutoQuad -- <http://autoquad.org>"]
1244 MAV_AUTOPILOT_AUTOQUAD = 14,
1245 #[doc = "Armazila -- <http://armazila.com>"]
1246 MAV_AUTOPILOT_ARMAZILA = 15,
1247 #[doc = "Aerob -- <http://aerob.ru>"]
1248 MAV_AUTOPILOT_AEROB = 16,
1249 #[doc = "ASLUAV autopilot -- <http://www.asl.ethz.ch>"]
1250 MAV_AUTOPILOT_ASLUAV = 17,
1251 #[doc = "SmartAP Autopilot - <http://sky-drones.com>"]
1252 MAV_AUTOPILOT_SMARTAP = 18,
1253 #[doc = "AirRails - <http://uaventure.com>"]
1254 MAV_AUTOPILOT_AIRRAILS = 19,
1255 #[doc = "Fusion Reflex - <https://fusion.engineering>"]
1256 MAV_AUTOPILOT_REFLEX = 20,
1257}
1258impl MavAutopilot {
1259 pub const DEFAULT: Self = Self::MAV_AUTOPILOT_GENERIC;
1260}
1261impl Default for MavAutopilot {
1262 fn default() -> Self {
1263 Self::DEFAULT
1264 }
1265}
1266#[cfg_attr(feature = "ts", derive(TS))]
1267#[cfg_attr(feature = "ts", ts(export))]
1268#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1269#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1270#[cfg_attr(feature = "serde", serde(tag = "type"))]
1271#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1272#[repr(u32)]
1273#[doc = "Enumeration for battery charge states."]
1274pub enum MavBatteryChargeState {
1275 #[doc = "Low battery state is not provided"]
1276 MAV_BATTERY_CHARGE_STATE_UNDEFINED = 0,
1277 #[doc = "Battery is not in low state. Normal operation."]
1278 MAV_BATTERY_CHARGE_STATE_OK = 1,
1279 #[doc = "Battery state is low, warn and monitor close."]
1280 MAV_BATTERY_CHARGE_STATE_LOW = 2,
1281 #[doc = "Battery state is critical, return or abort immediately."]
1282 MAV_BATTERY_CHARGE_STATE_CRITICAL = 3,
1283 #[doc = "Battery state is too low for ordinary abort sequence. Perform fastest possible emergency stop to prevent damage."]
1284 MAV_BATTERY_CHARGE_STATE_EMERGENCY = 4,
1285 #[doc = "Battery failed, damage unavoidable. Possible causes (faults) are listed in MAV_BATTERY_FAULT."]
1286 MAV_BATTERY_CHARGE_STATE_FAILED = 5,
1287 #[doc = "Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in MAV_BATTERY_FAULT."]
1288 MAV_BATTERY_CHARGE_STATE_UNHEALTHY = 6,
1289 #[doc = "Battery is charging."]
1290 MAV_BATTERY_CHARGE_STATE_CHARGING = 7,
1291}
1292impl MavBatteryChargeState {
1293 pub const DEFAULT: Self = Self::MAV_BATTERY_CHARGE_STATE_UNDEFINED;
1294}
1295impl Default for MavBatteryChargeState {
1296 fn default() -> Self {
1297 Self::DEFAULT
1298 }
1299}
1300bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Smart battery supply status/fault flags (bitmask) for health indication. The battery must also report either MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY if any of these are set."] pub struct MavBatteryFault : u32 { # [doc = "Battery has deep discharged."] const MAV_BATTERY_FAULT_DEEP_DISCHARGE = 1 ; # [doc = "Voltage spikes."] const MAV_BATTERY_FAULT_SPIKES = 2 ; # [doc = "One or more cells have failed. Battery should also report MAV_BATTERY_CHARGE_STATE_FAILE (and should not be used)."] const MAV_BATTERY_FAULT_CELL_FAIL = 4 ; # [doc = "Over-current fault."] const MAV_BATTERY_FAULT_OVER_CURRENT = 8 ; # [doc = "Over-temperature fault."] const MAV_BATTERY_FAULT_OVER_TEMPERATURE = 16 ; # [doc = "Under-temperature fault."] const MAV_BATTERY_FAULT_UNDER_TEMPERATURE = 32 ; # [doc = "Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage)."] const MAV_BATTERY_FAULT_INCOMPATIBLE_VOLTAGE = 64 ; # [doc = "Battery firmware is not compatible with current autopilot firmware."] const MAV_BATTERY_FAULT_INCOMPATIBLE_FIRMWARE = 128 ; # [doc = "Battery is not compatible due to cell configuration (e.g. 5s1p when vehicle requires 6s)."] const BATTERY_FAULT_INCOMPATIBLE_CELLS_CONFIGURATION = 256 ; } }
1301impl MavBatteryFault {
1302 pub const DEFAULT: Self = Self::MAV_BATTERY_FAULT_DEEP_DISCHARGE;
1303}
1304impl Default for MavBatteryFault {
1305 fn default() -> Self {
1306 Self::DEFAULT
1307 }
1308}
1309#[cfg_attr(feature = "ts", derive(TS))]
1310#[cfg_attr(feature = "ts", ts(export))]
1311#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1312#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1313#[cfg_attr(feature = "serde", serde(tag = "type"))]
1314#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1315#[repr(u32)]
1316#[doc = "Enumeration of battery functions"]
1317pub enum MavBatteryFunction {
1318 #[doc = "Battery function is unknown"]
1319 MAV_BATTERY_FUNCTION_UNKNOWN = 0,
1320 #[doc = "Battery supports all flight systems"]
1321 MAV_BATTERY_FUNCTION_ALL = 1,
1322 #[doc = "Battery for the propulsion system"]
1323 MAV_BATTERY_FUNCTION_PROPULSION = 2,
1324 #[doc = "Avionics battery"]
1325 MAV_BATTERY_FUNCTION_AVIONICS = 3,
1326 #[doc = "Payload battery"]
1327 MAV_BATTERY_FUNCTION_PAYLOAD = 4,
1328}
1329impl MavBatteryFunction {
1330 pub const DEFAULT: Self = Self::MAV_BATTERY_FUNCTION_UNKNOWN;
1331}
1332impl Default for MavBatteryFunction {
1333 fn default() -> Self {
1334 Self::DEFAULT
1335 }
1336}
1337#[cfg_attr(feature = "ts", derive(TS))]
1338#[cfg_attr(feature = "ts", ts(export))]
1339#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1340#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1341#[cfg_attr(feature = "serde", serde(tag = "type"))]
1342#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1343#[repr(u32)]
1344#[doc = "Battery mode. Note, the normal operation mode (i.e. when flying) should be reported as MAV_BATTERY_MODE_UNKNOWN to allow message trimming in normal flight."]
1345pub enum MavBatteryMode {
1346 #[doc = "Battery mode not supported/unknown battery mode/normal operation."]
1347 MAV_BATTERY_MODE_UNKNOWN = 0,
1348 #[doc = "Battery is auto discharging (towards storage level)."]
1349 MAV_BATTERY_MODE_AUTO_DISCHARGING = 1,
1350 #[doc = "Battery in hot-swap mode (current limited to prevent spikes that might damage sensitive electrical circuits)."]
1351 MAV_BATTERY_MODE_HOT_SWAP = 2,
1352}
1353impl MavBatteryMode {
1354 pub const DEFAULT: Self = Self::MAV_BATTERY_MODE_UNKNOWN;
1355}
1356impl Default for MavBatteryMode {
1357 fn default() -> Self {
1358 Self::DEFAULT
1359 }
1360}
1361#[cfg_attr(feature = "ts", derive(TS))]
1362#[cfg_attr(feature = "ts", ts(export))]
1363#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1364#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1365#[cfg_attr(feature = "serde", serde(tag = "type"))]
1366#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1367#[repr(u32)]
1368#[doc = "Enumeration of battery types"]
1369pub enum MavBatteryType {
1370 #[doc = "Not specified."]
1371 MAV_BATTERY_TYPE_UNKNOWN = 0,
1372 #[doc = "Lithium polymer battery"]
1373 MAV_BATTERY_TYPE_LIPO = 1,
1374 #[doc = "Lithium-iron-phosphate battery"]
1375 MAV_BATTERY_TYPE_LIFE = 2,
1376 #[doc = "Lithium-ION battery"]
1377 MAV_BATTERY_TYPE_LION = 3,
1378 #[doc = "Nickel metal hydride battery"]
1379 MAV_BATTERY_TYPE_NIMH = 4,
1380}
1381impl MavBatteryType {
1382 pub const DEFAULT: Self = Self::MAV_BATTERY_TYPE_UNKNOWN;
1383}
1384impl Default for MavBatteryType {
1385 fn default() -> Self {
1386 Self::DEFAULT
1387 }
1388}
1389#[cfg_attr(feature = "ts", derive(TS))]
1390#[cfg_attr(feature = "ts", ts(export))]
1391#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1392#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1393#[cfg_attr(feature = "serde", serde(tag = "type"))]
1394#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1395#[repr(u32)]
1396#[doc = "Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. NaN and INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current yaw or latitude rather than a specific value). See <https://mavlink.io/en/guide/xml_schema.html#MAV_CMD> for information about the structure of the MAV_CMD entries"]
1397pub enum MavCmd {
1398 #[doc = "Navigate to waypoint. This is intended for use in missions (for guided commands outside of missions use MAV_CMD_DO_REPOSITION)."]
1399 #[doc = ""]
1400 #[doc = "# Parameters"]
1401 #[doc = ""]
1402 #[doc = "| Parameter | Description | Values | Units |"]
1403 #[doc = "| --------- | ----------- | ------ | ----- |"]
1404 #[doc = "| 1 (Hold) | Hold time. (ignored by fixed wing, time to stay at waypoint for rotary wing)| ≥ 0 | s |"]
1405 #[doc = "| 2 (Accept Radius)| Acceptance radius (if the sphere with this radius is hit, the waypoint counts as reached)| ≥ 0 | m |"]
1406 #[doc = "| 3 (Pass Radius)| 0 to pass through the WP, if>0 radius to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| | m |"]
1407 #[doc = "| 4 (Yaw) | Desired yaw angle at waypoint (rotary wing). NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).| | deg |"]
1408 #[doc = "| 5 (Latitude)| Latitude | | |"]
1409 #[doc = "| 6 (Longitude)| Longitude | | |"]
1410 #[doc = "| 7 (Altitude)| Altitude | | m |"]
1411 MAV_CMD_NAV_WAYPOINT = 16,
1412 #[doc = "Loiter around this waypoint an unlimited amount of time"]
1413 #[doc = ""]
1414 #[doc = "# Parameters"]
1415 #[doc = ""]
1416 #[doc = "| Parameter | Description | Units |"]
1417 #[doc = "| --------- | ----------- | ----- |"]
1418 #[doc = "| 1 | Empty | |"]
1419 #[doc = "| 2 | Empty | |"]
1420 #[doc = "| 3 (Radius)| Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise| m |"]
1421 #[doc = "| 4 (Yaw) | Desired yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).| deg |"]
1422 #[doc = "| 5 (Latitude)| Latitude | |"]
1423 #[doc = "| 6 (Longitude)| Longitude | |"]
1424 #[doc = "| 7 (Altitude)| Altitude | m |"]
1425 MAV_CMD_NAV_LOITER_UNLIM = 17,
1426 #[doc = "Loiter around this waypoint for X turns"]
1427 #[doc = ""]
1428 #[doc = "# Parameters"]
1429 #[doc = ""]
1430 #[doc = "| Parameter | Description | Values | Units |"]
1431 #[doc = "| --------- | ----------- | ------ | ----- |"]
1432 #[doc = "| 1 (Turns) | Number of turns.| ≥ 0 | |"]
1433 #[doc = "| 2 (Heading Required)| Leave loiter circle only once heading towards the next waypoint (0 = False)| 0, 1 | |"]
1434 #[doc = "| 3 (Radius)| Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise| | m |"]
1435 #[doc = "| 4 (Xtrack Location)| Loiter circle exit location and/or path to next waypoint (\"xtrack\") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour.| | |"]
1436 #[doc = "| 5 (Latitude)| Latitude | | |"]
1437 #[doc = "| 6 (Longitude)| Longitude | | |"]
1438 #[doc = "| 7 (Altitude)| Altitude | | m |"]
1439 MAV_CMD_NAV_LOITER_TURNS = 18,
1440 #[doc = "Loiter at the specified latitude, longitude and altitude for a certain amount of time. Multicopter vehicles stop at the point (within a vehicle-specific acceptance radius). Forward-only moving vehicles (e.g. fixed-wing) circle the point with the specified radius/direction. If the Heading Required parameter (2) is non-zero forward moving aircraft will only leave the loiter circle once heading towards the next waypoint."]
1441 #[doc = ""]
1442 #[doc = "# Parameters"]
1443 #[doc = ""]
1444 #[doc = "| Parameter | Description | Values | Units |"]
1445 #[doc = "| --------- | ----------- | ------ | ----- |"]
1446 #[doc = "| 1 (Time) | Loiter time (only starts once Lat, Lon and Alt is reached).| ≥ 0 | s |"]
1447 #[doc = "| 2 (Heading Required)| Leave loiter circle only once heading towards the next waypoint (0 = False)| 0, 1 | |"]
1448 #[doc = "| 3 (Radius)| Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise.| | m |"]
1449 #[doc = "| 4 (Xtrack Location)| Loiter circle exit location and/or path to next waypoint (\"xtrack\") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour.| | |"]
1450 #[doc = "| 5 (Latitude)| Latitude | | |"]
1451 #[doc = "| 6 (Longitude)| Longitude | | |"]
1452 #[doc = "| 7 (Altitude)| Altitude | | m |"]
1453 MAV_CMD_NAV_LOITER_TIME = 19,
1454 #[doc = "Return to launch location"]
1455 #[doc = ""]
1456 #[doc = "# Parameters"]
1457 #[doc = ""]
1458 #[doc = "| Parameter | Description |"]
1459 #[doc = "| --------- | ----------- |"]
1460 #[doc = "| 1 | Empty |"]
1461 #[doc = "| 2 | Empty |"]
1462 #[doc = "| 3 | Empty |"]
1463 #[doc = "| 4 | Empty |"]
1464 #[doc = "| 5 | Empty |"]
1465 #[doc = "| 6 | Empty |"]
1466 #[doc = "| 7 | Empty |"]
1467 MAV_CMD_NAV_RETURN_TO_LAUNCH = 20,
1468 #[doc = "Land at location."]
1469 #[doc = ""]
1470 #[doc = "# Parameters"]
1471 #[doc = ""]
1472 #[doc = "| Parameter | Description | Values | Units |"]
1473 #[doc = "| --------- | ----------- | ------ | ----- |"]
1474 #[doc = "| 1 (Abort Alt)| Minimum target altitude if landing is aborted (0 = undefined/use system default).| | m |"]
1475 #[doc = "| 2 (Land Mode)| Precision land mode.| [`PrecisionLandMode`] | |"]
1476 #[doc = "| 3 | Empty. | | |"]
1477 #[doc = "| 4 (Yaw Angle)| Desired yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).| | deg |"]
1478 #[doc = "| 5 (Latitude)| Latitude. | | |"]
1479 #[doc = "| 6 (Longitude)| Longitude. | | |"]
1480 #[doc = "| 7 (Altitude)| Landing altitude (ground level in current frame).| | m |"]
1481 MAV_CMD_NAV_LAND = 21,
1482 #[doc = "Takeoff from ground / hand. Vehicles that support multiple takeoff modes (e.g. VTOL quadplane) should take off using the currently configured mode."]
1483 #[doc = ""]
1484 #[doc = "# Parameters"]
1485 #[doc = ""]
1486 #[doc = "| Parameter | Description | Units |"]
1487 #[doc = "| --------- | ----------- | ----- |"]
1488 #[doc = "| 1 (Pitch) | Minimum pitch (if airspeed sensor present), desired pitch without sensor| deg |"]
1489 #[doc = "| 2 | Empty | |"]
1490 #[doc = "| 3 | Empty | |"]
1491 #[doc = "| 4 (Yaw) | Yaw angle (if magnetometer present), ignored without magnetometer. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).| deg |"]
1492 #[doc = "| 5 (Latitude)| Latitude | |"]
1493 #[doc = "| 6 (Longitude)| Longitude | |"]
1494 #[doc = "| 7 (Altitude)| Altitude | m |"]
1495 MAV_CMD_NAV_TAKEOFF = 22,
1496 #[doc = "Land at local position (local frame only)"]
1497 #[doc = ""]
1498 #[doc = "# Parameters"]
1499 #[doc = ""]
1500 #[doc = "| Parameter | Description | Values | Units |"]
1501 #[doc = "| --------- | ----------- | ------ | ----- |"]
1502 #[doc = "| 1 (Target)| Landing target number (if available)| 0, 1, .. | |"]
1503 #[doc = "| 2 (Offset)| Maximum accepted offset from desired landing position - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land| ≥ 0 | m |"]
1504 #[doc = "| 3 (Descend Rate)| Landing descend rate| | m/s |"]
1505 #[doc = "| 4 (Yaw) | Desired yaw angle| | rad |"]
1506 #[doc = "| 5 (Y Position)| Y-axis position| | m |"]
1507 #[doc = "| 6 (X Position)| X-axis position| | m |"]
1508 #[doc = "| 7 (Z Position)| Z-axis / ground level position| | m |"]
1509 MAV_CMD_NAV_LAND_LOCAL = 23,
1510 #[doc = "Takeoff from local position (local frame only)"]
1511 #[doc = ""]
1512 #[doc = "# Parameters"]
1513 #[doc = ""]
1514 #[doc = "| Parameter | Description | Units |"]
1515 #[doc = "| --------- | ----------- | ----- |"]
1516 #[doc = "| 1 (Pitch) | Minimum pitch (if airspeed sensor present), desired pitch without sensor| rad |"]
1517 #[doc = "| 2 | Empty | |"]
1518 #[doc = "| 3 (Ascend Rate)| Takeoff ascend rate| m/s |"]
1519 #[doc = "| 4 (Yaw) | Yaw angle (if magnetometer or another yaw estimation source present), ignored without one of these| rad |"]
1520 #[doc = "| 5 (Y Position)| Y-axis position| m |"]
1521 #[doc = "| 6 (X Position)| X-axis position| m |"]
1522 #[doc = "| 7 (Z Position)| Z-axis position| m |"]
1523 MAV_CMD_NAV_TAKEOFF_LOCAL = 24,
1524 #[doc = "Vehicle following, i.e. this waypoint represents the position of a moving vehicle"]
1525 #[doc = ""]
1526 #[doc = "# Parameters"]
1527 #[doc = ""]
1528 #[doc = "| Parameter | Description | Values | Units |"]
1529 #[doc = "| --------- | ----------- | ------ | ----- |"]
1530 #[doc = "| 1 (Following)| Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation| Multiples of 1 | |"]
1531 #[doc = "| 2 (Ground Speed)| Ground speed of vehicle to be followed| | m/s |"]
1532 #[doc = "| 3 (Radius)| Radius around waypoint. If positive loiter clockwise, else counter-clockwise| | m |"]
1533 #[doc = "| 4 (Yaw) | Desired yaw angle.| | deg |"]
1534 #[doc = "| 5 (Latitude)| Latitude | | |"]
1535 #[doc = "| 6 (Longitude)| Longitude | | |"]
1536 #[doc = "| 7 (Altitude)| Altitude | | m |"]
1537 MAV_CMD_NAV_FOLLOW = 25,
1538 #[doc = "Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached."]
1539 #[doc = ""]
1540 #[doc = "# Parameters"]
1541 #[doc = ""]
1542 #[doc = "| Parameter | Description | Values | Units |"]
1543 #[doc = "| --------- | ----------- | ------ | ----- |"]
1544 #[doc = "| 1 (Action)| Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude.| 0, 1, 2 | |"]
1545 #[doc = "| 2 | Empty | | |"]
1546 #[doc = "| 3 | Empty | | |"]
1547 #[doc = "| 4 | Empty | | |"]
1548 #[doc = "| 5 | Empty | | |"]
1549 #[doc = "| 6 | Empty | | |"]
1550 #[doc = "| 7 (Altitude)| Desired altitude| | m |"]
1551 MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT = 30,
1552 #[doc = "Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint."]
1553 #[doc = ""]
1554 #[doc = "# Parameters"]
1555 #[doc = ""]
1556 #[doc = "| Parameter | Description | Values | Units |"]
1557 #[doc = "| --------- | ----------- | ------ | ----- |"]
1558 #[doc = "| 1 (Heading Required)| Leave loiter circle only once heading towards the next waypoint (0 = False)| 0, 1 | |"]
1559 #[doc = "| 2 (Radius)| Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.| | m |"]
1560 #[doc = "| 3 | Empty | | |"]
1561 #[doc = "| 4 (Xtrack Location)| Loiter circle exit location and/or path to next waypoint (\"xtrack\") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour.| 0, 1 | |"]
1562 #[doc = "| 5 (Latitude)| Latitude | | |"]
1563 #[doc = "| 6 (Longitude)| Longitude | | |"]
1564 #[doc = "| 7 (Altitude)| Altitude | | m |"]
1565 MAV_CMD_NAV_LOITER_TO_ALT = 31,
1566 #[doc = "Begin following a target"]
1567 #[doc = ""]
1568 #[doc = "# Parameters"]
1569 #[doc = ""]
1570 #[doc = "| Parameter | Description | Values | Units |"]
1571 #[doc = "| --------- | ----------- | ------ | ----- |"]
1572 #[doc = "| 1 (System ID)| System ID (of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode.| 0, 1, .. , 255 | |"]
1573 #[doc = "| 2 | Reserved | | |"]
1574 #[doc = "| 3 | Reserved | | |"]
1575 #[doc = "| 4 (Altitude Mode)| Altitude mode: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home.| 0, 1, 2 | |"]
1576 #[doc = "| 5 (Altitude)| Altitude above home. (used if mode=2)| | m |"]
1577 #[doc = "| 6 | Reserved | | |"]
1578 #[doc = "| 7 (Time to Land)| Time to land in which the MAV should go to the default position hold mode after a message RX timeout.| ≥ 0 | s |"]
1579 MAV_CMD_DO_FOLLOW = 32,
1580 #[doc = "Reposition the MAV after a follow target command has been sent"]
1581 #[doc = ""]
1582 #[doc = "# Parameters"]
1583 #[doc = ""]
1584 #[doc = "| Parameter | Description | Units |"]
1585 #[doc = "| --------- | ----------- | ----- |"]
1586 #[doc = "| 1 (Camera Q1)| Camera q1 (where 0 is on the ray from the camera to the tracking device)| |"]
1587 #[doc = "| 2 (Camera Q2)| Camera q2 | |"]
1588 #[doc = "| 3 (Camera Q3)| Camera q3 | |"]
1589 #[doc = "| 4 (Camera Q4)| Camera q4 | |"]
1590 #[doc = "| 5 (Altitude Offset)| altitude offset from target| m |"]
1591 #[doc = "| 6 (X Offset)| X offset from target| m |"]
1592 #[doc = "| 7 (Y Offset)| Y offset from target| m |"]
1593 MAV_CMD_DO_FOLLOW_REPOSITION = 33,
1594 #[doc = "Start orbiting on the circumference of a circle defined by the parameters. Setting values to NaN/INT32_MAX (as appropriate) results in using defaults."]
1595 #[doc = ""]
1596 #[doc = "# Parameters"]
1597 #[doc = ""]
1598 #[doc = "| Parameter | Description | Values | Units |"]
1599 #[doc = "| --------- | ----------- | ------ | ----- |"]
1600 #[doc = "| 1 (Radius)| Radius of the circle. Positive: orbit clockwise. Negative: orbit counter-clockwise. NaN: Use vehicle default radius, or current radius if already orbiting.| | m |"]
1601 #[doc = "| 2 (Velocity)| Tangential Velocity. NaN: Use vehicle default velocity, or current velocity if already orbiting.| | m/s |"]
1602 #[doc = "| 3 (Yaw Behavior)| Yaw behavior of the vehicle.| [`OrbitYawBehaviour`] | |"]
1603 #[doc = "| 4 (Orbits)| Orbit around the centre point for this many radians (i.e. for a three-quarter orbit set 270*Pi/180). 0: Orbit forever. NaN: Use vehicle default, or current value if already orbiting.| ≥ 0 | rad |"]
1604 #[doc = "| 5 (Latitude/X)| Center point latitude (if no MAV_FRAME specified) / X coordinate according to MAV_FRAME. INT32_MAX (or NaN if sent in COMMAND_LONG): Use current vehicle position, or current center if already orbiting.| | |"]
1605 #[doc = "| 6 (Longitude/Y)| Center point longitude (if no MAV_FRAME specified) / Y coordinate according to MAV_FRAME. INT32_MAX (or NaN if sent in COMMAND_LONG): Use current vehicle position, or current center if already orbiting.| | |"]
1606 #[doc = "| 7 (Altitude/Z)| Center point altitude (MSL) (if no MAV_FRAME specified) / Z coordinate according to MAV_FRAME. NaN: Use current vehicle altitude.| | |"]
1607 MAV_CMD_DO_ORBIT = 34,
1608 #[deprecated = " See `MAV_CMD_DO_SET_ROI_*` (Deprecated since 2018-01)"]
1609 #[doc = "Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras."]
1610 #[doc = ""]
1611 #[doc = "# Parameters"]
1612 #[doc = ""]
1613 #[doc = "| Parameter | Description | Values |"]
1614 #[doc = "| --------- | ----------- | ------ |"]
1615 #[doc = "| 1 (ROI Mode)| Region of interest mode.| [`MavRoi`] |"]
1616 #[doc = "| 2 (WP Index)| Waypoint index/ target ID. (see MAV_ROI enum)| 0, 1, .. |"]
1617 #[doc = "| 3 (ROI Index)| ROI index (allows a vehicle to manage multiple ROI's)| 0, 1, .. |"]
1618 #[doc = "| 4 | Empty | |"]
1619 #[doc = "| 5 (X) | x the location of the fixed ROI (see MAV_FRAME)| |"]
1620 #[doc = "| 6 (Y) | y | |"]
1621 #[doc = "| 7 (Z) | z | |"]
1622 MAV_CMD_NAV_ROI = 80,
1623 #[doc = "Control autonomous path planning on the MAV."]
1624 #[doc = ""]
1625 #[doc = "# Parameters"]
1626 #[doc = ""]
1627 #[doc = "| Parameter | Description | Values | Units |"]
1628 #[doc = "| --------- | ----------- | ------ | ----- |"]
1629 #[doc = "| 1 (Local Ctrl)| 0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0, 1, 2 | |"]
1630 #[doc = "| 2 (Global Ctrl)| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| 0, 1, .. , 3 | |"]
1631 #[doc = "| 3 | Empty | | |"]
1632 #[doc = "| 4 (Yaw) | Yaw angle at goal| | deg |"]
1633 #[doc = "| 5 (Latitude/X)| Latitude/X of goal| | |"]
1634 #[doc = "| 6 (Longitude/Y)| Longitude/Y of goal| | |"]
1635 #[doc = "| 7 (Altitude/Z)| Altitude/Z of goal| | |"]
1636 MAV_CMD_NAV_PATHPLANNING = 81,
1637 #[doc = "Navigate to waypoint using a spline path."]
1638 #[doc = ""]
1639 #[doc = "# Parameters"]
1640 #[doc = ""]
1641 #[doc = "| Parameter | Description | Values | Units |"]
1642 #[doc = "| --------- | ----------- | ------ | ----- |"]
1643 #[doc = "| 1 (Hold) | Hold time. (ignored by fixed wing, time to stay at waypoint for rotary wing)| ≥ 0 | s |"]
1644 #[doc = "| 2 | Empty | | |"]
1645 #[doc = "| 3 | Empty | | |"]
1646 #[doc = "| 4 | Empty | | |"]
1647 #[doc = "| 5 (Latitude/X)| Latitude/X of goal| | |"]
1648 #[doc = "| 6 (Longitude/Y)| Longitude/Y of goal| | |"]
1649 #[doc = "| 7 (Altitude/Z)| Altitude/Z of goal| | |"]
1650 MAV_CMD_NAV_SPLINE_WAYPOINT = 82,
1651 #[doc = "Takeoff from ground using VTOL mode, and transition to forward flight with specified heading. The command should be ignored by vehicles that dont support both VTOL and fixed-wing flight (multicopters, boats,etc.)."]
1652 #[doc = ""]
1653 #[doc = "# Parameters"]
1654 #[doc = ""]
1655 #[doc = "| Parameter | Description | Values | Units |"]
1656 #[doc = "| --------- | ----------- | ------ | ----- |"]
1657 #[doc = "| 1 | Empty | | |"]
1658 #[doc = "| 2 (Transition Heading)| Front transition heading.| [`VtolTransitionHeading`] | |"]
1659 #[doc = "| 3 | Empty | | |"]
1660 #[doc = "| 4 (Yaw Angle)| Yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).| | deg |"]
1661 #[doc = "| 5 (Latitude)| Latitude | | |"]
1662 #[doc = "| 6 (Longitude)| Longitude | | |"]
1663 #[doc = "| 7 (Altitude)| Altitude | | m |"]
1664 MAV_CMD_NAV_VTOL_TAKEOFF = 84,
1665 #[doc = "Land using VTOL mode"]
1666 #[doc = ""]
1667 #[doc = "# Parameters"]
1668 #[doc = ""]
1669 #[doc = "| Parameter | Description | Values | Units |"]
1670 #[doc = "| --------- | ----------- | ------ | ----- |"]
1671 #[doc = "| 1 (Land Options)| Landing behaviour.| [`NavVtolLandOptions`] | |"]
1672 #[doc = "| 2 | Empty | | |"]
1673 #[doc = "| 3 (Approach Altitude)| Approach altitude (with the same reference as the Altitude field). NaN if unspecified.| | m |"]
1674 #[doc = "| 4 (Yaw) | Yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).| | deg |"]
1675 #[doc = "| 5 (Latitude)| Latitude | | |"]
1676 #[doc = "| 6 (Longitude)| Longitude | | |"]
1677 #[doc = "| 7 (Ground Altitude)| Altitude (ground level) relative to the current coordinate frame. NaN to use system default landing altitude (ignore value).| | m |"]
1678 MAV_CMD_NAV_VTOL_LAND = 85,
1679 #[doc = "hand control over to an external controller"]
1680 #[doc = ""]
1681 #[doc = "# Parameters"]
1682 #[doc = ""]
1683 #[doc = "| Parameter | Description | Values |"]
1684 #[doc = "| --------- | ----------- | ------ |"]
1685 #[doc = "| 1 (Enable)| On / Off (>0.5f on)| 0, 1 |"]
1686 #[doc = "| 2 | Empty | |"]
1687 #[doc = "| 3 | Empty | |"]
1688 #[doc = "| 4 | Empty | |"]
1689 #[doc = "| 5 | Empty | |"]
1690 #[doc = "| 6 | Empty | |"]
1691 #[doc = "| 7 | Empty | |"]
1692 MAV_CMD_NAV_GUIDED_ENABLE = 92,
1693 #[doc = "Delay the next navigation command a number of seconds or until a specified time"]
1694 #[doc = ""]
1695 #[doc = "# Parameters"]
1696 #[doc = ""]
1697 #[doc = "| Parameter | Description | Values | Units |"]
1698 #[doc = "| --------- | ----------- | ------ | ----- |"]
1699 #[doc = "| 1 (Delay) | Delay (-1 to enable time-of-day fields)| -1, 0, .. | s |"]
1700 #[doc = "| 2 (Hour) | hour (24h format, UTC, -1 to ignore)| -1, 0, .. , 23 | |"]
1701 #[doc = "| 3 (Minute)| minute (24h format, UTC, -1 to ignore)| -1, 0, .. , 59 | |"]
1702 #[doc = "| 4 (Second)| second (24h format, UTC, -1 to ignore)| -1, 0, .. , 59 | |"]
1703 #[doc = "| 5 | Empty | | |"]
1704 #[doc = "| 6 | Empty | | |"]
1705 #[doc = "| 7 | Empty | | |"]
1706 MAV_CMD_NAV_DELAY = 93,
1707 #[doc = "Descend and place payload. Vehicle moves to specified location, descends until it detects a hanging payload has reached the ground, and then releases the payload. If ground is not detected before the reaching the maximum descent value (param1), the command will complete without releasing the payload."]
1708 #[doc = ""]
1709 #[doc = "# Parameters"]
1710 #[doc = ""]
1711 #[doc = "| Parameter | Description | Values | Units |"]
1712 #[doc = "| --------- | ----------- | ------ | ----- |"]
1713 #[doc = "| 1 (Max Descent)| Maximum distance to descend.| ≥ 0 | m |"]
1714 #[doc = "| 2 | Empty | | |"]
1715 #[doc = "| 3 | Empty | | |"]
1716 #[doc = "| 4 | Empty | | |"]
1717 #[doc = "| 5 (Latitude)| Latitude | | |"]
1718 #[doc = "| 6 (Longitude)| Longitude | | |"]
1719 #[doc = "| 7 (Altitude)| Altitude | | m |"]
1720 MAV_CMD_NAV_PAYLOAD_PLACE = 94,
1721 #[doc = "NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration"]
1722 #[doc = ""]
1723 #[doc = "# Parameters"]
1724 #[doc = ""]
1725 #[doc = "| Parameter | Description |"]
1726 #[doc = "| --------- | ----------- |"]
1727 #[doc = "| 1 | Empty |"]
1728 #[doc = "| 2 | Empty |"]
1729 #[doc = "| 3 | Empty |"]
1730 #[doc = "| 4 | Empty |"]
1731 #[doc = "| 5 | Empty |"]
1732 #[doc = "| 6 | Empty |"]
1733 #[doc = "| 7 | Empty |"]
1734 MAV_CMD_NAV_LAST = 95,
1735 #[doc = "Delay mission state machine."]
1736 #[doc = ""]
1737 #[doc = "# Parameters"]
1738 #[doc = ""]
1739 #[doc = "| Parameter | Description | Values | Units |"]
1740 #[doc = "| --------- | ----------- | ------ | ----- |"]
1741 #[doc = "| 1 (Delay) | Delay | ≥ 0 | s |"]
1742 #[doc = "| 2 | Empty | | |"]
1743 #[doc = "| 3 | Empty | | |"]
1744 #[doc = "| 4 | Empty | | |"]
1745 #[doc = "| 5 | Empty | | |"]
1746 #[doc = "| 6 | Empty | | |"]
1747 #[doc = "| 7 | Empty | | |"]
1748 MAV_CMD_CONDITION_DELAY = 112,
1749 #[doc = "Ascend/descend to target altitude at specified rate. Delay mission state machine until desired altitude reached."]
1750 #[doc = ""]
1751 #[doc = "# Parameters"]
1752 #[doc = ""]
1753 #[doc = "| Parameter | Description | Units |"]
1754 #[doc = "| --------- | ----------- | ----- |"]
1755 #[doc = "| 1 (Rate) | Descent / Ascend rate.| m/s |"]
1756 #[doc = "| 2 | Empty | |"]
1757 #[doc = "| 3 | Empty | |"]
1758 #[doc = "| 4 | Empty | |"]
1759 #[doc = "| 5 | Empty | |"]
1760 #[doc = "| 6 | Empty | |"]
1761 #[doc = "| 7 (Altitude)| Target Altitude| m |"]
1762 MAV_CMD_CONDITION_CHANGE_ALT = 113,
1763 #[doc = "Delay mission state machine until within desired distance of next NAV point."]
1764 #[doc = ""]
1765 #[doc = "# Parameters"]
1766 #[doc = ""]
1767 #[doc = "| Parameter | Description | Values | Units |"]
1768 #[doc = "| --------- | ----------- | ------ | ----- |"]
1769 #[doc = "| 1 (Distance)| Distance. | ≥ 0 | m |"]
1770 #[doc = "| 2 | Empty | | |"]
1771 #[doc = "| 3 | Empty | | |"]
1772 #[doc = "| 4 | Empty | | |"]
1773 #[doc = "| 5 | Empty | | |"]
1774 #[doc = "| 6 | Empty | | |"]
1775 #[doc = "| 7 | Empty | | |"]
1776 MAV_CMD_CONDITION_DISTANCE = 114,
1777 #[doc = "Reach a certain target angle."]
1778 #[doc = ""]
1779 #[doc = "# Parameters"]
1780 #[doc = ""]
1781 #[doc = "| Parameter | Description | Values | Units |"]
1782 #[doc = "| --------- | ----------- | ------ | ----- |"]
1783 #[doc = "| 1 (Angle) | target angle [0-360]. Absolute angles: 0 is north. Relative angle: 0 is initial yaw. Direction set by param3.| 0 .. 360 | deg |"]
1784 #[doc = "| 2 (Angular Speed)| angular speed| ≥ 0 | deg/s |"]
1785 #[doc = "| 3 (Direction)| direction: -1: counter clockwise, 0: shortest direction, 1: clockwise| -1, 0, 1 | |"]
1786 #[doc = "| 4 (Relative)| 0: absolute angle, 1: relative offset| 0, 1 | |"]
1787 #[doc = "| 5 | Empty | | |"]
1788 #[doc = "| 6 | Empty | | |"]
1789 #[doc = "| 7 | Empty | | |"]
1790 MAV_CMD_CONDITION_YAW = 115,
1791 #[doc = "NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration"]
1792 #[doc = ""]
1793 #[doc = "# Parameters"]
1794 #[doc = ""]
1795 #[doc = "| Parameter | Description |"]
1796 #[doc = "| --------- | ----------- |"]
1797 #[doc = "| 1 | Empty |"]
1798 #[doc = "| 2 | Empty |"]
1799 #[doc = "| 3 | Empty |"]
1800 #[doc = "| 4 | Empty |"]
1801 #[doc = "| 5 | Empty |"]
1802 #[doc = "| 6 | Empty |"]
1803 #[doc = "| 7 | Empty |"]
1804 MAV_CMD_CONDITION_LAST = 159,
1805 #[doc = "Set system mode."]
1806 #[doc = ""]
1807 #[doc = "# Parameters"]
1808 #[doc = ""]
1809 #[doc = "| Parameter | Description | Values |"]
1810 #[doc = "| --------- | ----------- | ------ |"]
1811 #[doc = "| 1 (Mode) | Mode | [`MavMode`] |"]
1812 #[doc = "| 2 (Custom Mode)| Custom mode - this is system specific, please refer to the individual autopilot specifications for details.| |"]
1813 #[doc = "| 3 (Custom Submode)| Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details.| |"]
1814 #[doc = "| 4 | Empty | |"]
1815 #[doc = "| 5 | Empty | |"]
1816 #[doc = "| 6 | Empty | |"]
1817 #[doc = "| 7 | Empty | |"]
1818 MAV_CMD_DO_SET_MODE = 176,
1819 #[doc = "Jump to the desired command in the mission list. Repeat this action only the specified number of times"]
1820 #[doc = ""]
1821 #[doc = "# Parameters"]
1822 #[doc = ""]
1823 #[doc = "| Parameter | Description | Values |"]
1824 #[doc = "| --------- | ----------- | ------ |"]
1825 #[doc = "| 1 (Number)| Sequence number| 0, 1, .. |"]
1826 #[doc = "| 2 (Repeat)| Repeat count| 0, 1, .. |"]
1827 #[doc = "| 3 | Empty | |"]
1828 #[doc = "| 4 | Empty | |"]
1829 #[doc = "| 5 | Empty | |"]
1830 #[doc = "| 6 | Empty | |"]
1831 #[doc = "| 7 | Empty | |"]
1832 MAV_CMD_DO_JUMP = 177,
1833 #[doc = "Change speed and/or throttle set points. The value persists until it is overridden or there is a mode change"]
1834 #[doc = ""]
1835 #[doc = "# Parameters"]
1836 #[doc = ""]
1837 #[doc = "| Parameter | Description | Values | Units |"]
1838 #[doc = "| --------- | ----------- | ------ | ----- |"]
1839 #[doc = "| 1 (Speed Type)| Speed type of value set in param2 (such as airspeed, ground speed, and so on)| [`SpeedType`] | |"]
1840 #[doc = "| 2 (Speed) | Speed (-1 indicates no change, -2 indicates return to default vehicle speed)| ≥ -2 | m/s |"]
1841 #[doc = "| 3 (Throttle)| Throttle (-1 indicates no change, -2 indicates return to default vehicle throttle value)| ≥ -2 | % |"]
1842 #[doc = "| 4 | | Reserved (use 0) | |"]
1843 #[doc = "| 5 | | Reserved (use 0) | |"]
1844 #[doc = "| 6 | | Reserved (use 0) | |"]
1845 #[doc = "| 7 | | Reserved (use 0) | |"]
1846 MAV_CMD_DO_CHANGE_SPEED = 178,
1847 #[doc = "Sets the home position to either to the current position or a specified position. The home position is the default position that the system will return to and land on. The position is set automatically by the system during the takeoff (and may also be set using this command). Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242)."]
1848 #[doc = ""]
1849 #[doc = "# Parameters"]
1850 #[doc = ""]
1851 #[doc = "| Parameter | Description | Values | Units |"]
1852 #[doc = "| --------- | ----------- | ------ | ----- |"]
1853 #[doc = "| 1 (Use Current)| Use current (1=use current location, 0=use specified location)| 0, 1 | |"]
1854 #[doc = "| 2 (Roll) | Roll angle (of surface). Range: -180..180 degrees. NAN or 0 means value not set. 0.01 indicates zero roll.| -180 .. 180 | deg |"]
1855 #[doc = "| 3 (Pitch) | Pitch angle (of surface). Range: -90..90 degrees. NAN or 0 means value not set. 0.01 means zero pitch.| -90 .. 90 | deg |"]
1856 #[doc = "| 4 (Yaw) | Yaw angle. NaN to use default heading. Range: -180..180 degrees.| -180 .. 180 | deg |"]
1857 #[doc = "| 5 (Latitude)| Latitude | | |"]
1858 #[doc = "| 6 (Longitude)| Longitude | | |"]
1859 #[doc = "| 7 (Altitude)| Altitude | | m |"]
1860 MAV_CMD_DO_SET_HOME = 179,
1861 #[deprecated = " See `PARAM_SET` (Deprecated since 2024-04)"]
1862 #[doc = "Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter."]
1863 #[doc = ""]
1864 #[doc = "# Parameters"]
1865 #[doc = ""]
1866 #[doc = "| Parameter | Description | Values |"]
1867 #[doc = "| --------- | ----------- | ------ |"]
1868 #[doc = "| 1 (Number)| Parameter number| 0, 1, .. |"]
1869 #[doc = "| 2 (Value) | Parameter value| |"]
1870 #[doc = "| 3 | Empty | |"]
1871 #[doc = "| 4 | Empty | |"]
1872 #[doc = "| 5 | Empty | |"]
1873 #[doc = "| 6 | Empty | |"]
1874 #[doc = "| 7 | Empty | |"]
1875 MAV_CMD_DO_SET_PARAMETER = 180,
1876 #[doc = "Set a relay to a condition."]
1877 #[doc = ""]
1878 #[doc = "# Parameters"]
1879 #[doc = ""]
1880 #[doc = "| Parameter | Description | Values |"]
1881 #[doc = "| --------- | ----------- | ------ |"]
1882 #[doc = "| 1 (Instance)| Relay instance number.| 0, 1, .. |"]
1883 #[doc = "| 2 (Setting)| Setting. (1=on, 0=off, others possible depending on system hardware)| 0, 1, .. |"]
1884 #[doc = "| 3 | Empty | |"]
1885 #[doc = "| 4 | Empty | |"]
1886 #[doc = "| 5 | Empty | |"]
1887 #[doc = "| 6 | Empty | |"]
1888 #[doc = "| 7 | Empty | |"]
1889 MAV_CMD_DO_SET_RELAY = 181,
1890 #[doc = "Cycle a relay on and off for a desired number of cycles with a desired period."]
1891 #[doc = ""]
1892 #[doc = "# Parameters"]
1893 #[doc = ""]
1894 #[doc = "| Parameter | Description | Values | Units |"]
1895 #[doc = "| --------- | ----------- | ------ | ----- |"]
1896 #[doc = "| 1 (Instance)| Relay instance number.| 0, 1, .. | |"]
1897 #[doc = "| 2 (Count) | Cycle count.| 1, 2, .. | |"]
1898 #[doc = "| 3 (Time) | Cycle time. | ≥ 0 | s |"]
1899 #[doc = "| 4 | Empty | | |"]
1900 #[doc = "| 5 | Empty | | |"]
1901 #[doc = "| 6 | Empty | | |"]
1902 #[doc = "| 7 | Empty | | |"]
1903 MAV_CMD_DO_REPEAT_RELAY = 182,
1904 #[doc = "Set a servo to a desired PWM value."]
1905 #[doc = ""]
1906 #[doc = "# Parameters"]
1907 #[doc = ""]
1908 #[doc = "| Parameter | Description | Values | Units |"]
1909 #[doc = "| --------- | ----------- | ------ | ----- |"]
1910 #[doc = "| 1 (Instance)| Servo instance number.| 0, 1, .. | |"]
1911 #[doc = "| 2 (PWM) | Pulse Width Modulation.| 0, 1, .. | us |"]
1912 #[doc = "| 3 | Empty | | |"]
1913 #[doc = "| 4 | Empty | | |"]
1914 #[doc = "| 5 | Empty | | |"]
1915 #[doc = "| 6 | Empty | | |"]
1916 #[doc = "| 7 | Empty | | |"]
1917 MAV_CMD_DO_SET_SERVO = 183,
1918 #[doc = "Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period."]
1919 #[doc = ""]
1920 #[doc = "# Parameters"]
1921 #[doc = ""]
1922 #[doc = "| Parameter | Description | Values | Units |"]
1923 #[doc = "| --------- | ----------- | ------ | ----- |"]
1924 #[doc = "| 1 (Instance)| Servo instance number.| 0, 1, .. | |"]
1925 #[doc = "| 2 (PWM) | Pulse Width Modulation.| 0, 1, .. | us |"]
1926 #[doc = "| 3 (Count) | Cycle count.| 1, 2, .. | |"]
1927 #[doc = "| 4 (Time) | Cycle time. | ≥ 0 | s |"]
1928 #[doc = "| 5 | Empty | | |"]
1929 #[doc = "| 6 | Empty | | |"]
1930 #[doc = "| 7 | Empty | | |"]
1931 MAV_CMD_DO_REPEAT_SERVO = 184,
1932 #[doc = "Terminate flight immediately. Flight termination immediately and irreversibly terminates the current flight, returning the vehicle to ground. The vehicle will ignore RC or other input until it has been power-cycled. Termination may trigger safety measures, including: disabling motors and deployment of parachute on multicopters, and setting flight surfaces to initiate a landing pattern on fixed-wing). On multicopters without a parachute it may trigger a crash landing. Support for this command can be tested using the protocol bit: MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION. Support for this command can also be tested by sending the command with param1=0 (<0.5); the ACK should be either MAV_RESULT_FAILED or MAV_RESULT_UNSUPPORTED."]
1933 #[doc = ""]
1934 #[doc = "# Parameters"]
1935 #[doc = ""]
1936 #[doc = "| Parameter | Description | Values |"]
1937 #[doc = "| --------- | ----------- | ------ |"]
1938 #[doc = "| 1 (Terminate)| Flight termination activated if>0.5. Otherwise not activated and ACK with MAV_RESULT_FAILED.| 0, 1 |"]
1939 #[doc = "| 2 | Empty | |"]
1940 #[doc = "| 3 | Empty | |"]
1941 #[doc = "| 4 | Empty | |"]
1942 #[doc = "| 5 | Empty | |"]
1943 #[doc = "| 6 | Empty | |"]
1944 #[doc = "| 7 | Empty | |"]
1945 MAV_CMD_DO_FLIGHTTERMINATION = 185,
1946 #[doc = "Change altitude set point."]
1947 #[doc = ""]
1948 #[doc = "# Parameters"]
1949 #[doc = ""]
1950 #[doc = "| Parameter | Description | Values | Units |"]
1951 #[doc = "| --------- | ----------- | ------ | ----- |"]
1952 #[doc = "| 1 (Altitude)| Altitude. | | m |"]
1953 #[doc = "| 2 (Frame) | Frame of new altitude.| [`MavFrame`] | |"]
1954 #[doc = "| 3 | Empty | | |"]
1955 #[doc = "| 4 | Empty | | |"]
1956 #[doc = "| 5 | Empty | | |"]
1957 #[doc = "| 6 | Empty | | |"]
1958 #[doc = "| 7 | Empty | | |"]
1959 MAV_CMD_DO_CHANGE_ALTITUDE = 186,
1960 #[doc = "Sets actuators (e.g. servos) to a desired value. The actuator numbers are mapped to specific outputs (e.g. on any MAIN or AUX PWM or UAVCAN) using a flight-stack specific mechanism (i.e. a parameter)."]
1961 #[doc = ""]
1962 #[doc = "# Parameters"]
1963 #[doc = ""]
1964 #[doc = "| Parameter | Description | Values |"]
1965 #[doc = "| --------- | ----------- | ------ |"]
1966 #[doc = "| 1 (Actuator 1)| Actuator 1 value, scaled from [-1 to 1]. NaN to ignore.| -1 .. 1 |"]
1967 #[doc = "| 2 (Actuator 2)| Actuator 2 value, scaled from [-1 to 1]. NaN to ignore.| -1 .. 1 |"]
1968 #[doc = "| 3 (Actuator 3)| Actuator 3 value, scaled from [-1 to 1]. NaN to ignore.| -1 .. 1 |"]
1969 #[doc = "| 4 (Actuator 4)| Actuator 4 value, scaled from [-1 to 1]. NaN to ignore.| -1 .. 1 |"]
1970 #[doc = "| 5 (Actuator 5)| Actuator 5 value, scaled from [-1 to 1]. NaN to ignore.| -1 .. 1 |"]
1971 #[doc = "| 6 (Actuator 6)| Actuator 6 value, scaled from [-1 to 1]. NaN to ignore.| -1 .. 1 |"]
1972 #[doc = "| 7 (Index) | Index of actuator set (i.e if set to 1, Actuator 1 becomes Actuator 7)| 0, 1, .. |"]
1973 MAV_CMD_DO_SET_ACTUATOR = 187,
1974 #[doc = "Mission item to specify the start of a failsafe/landing return-path segment (the end of the segment is the next MAV_CMD_DO_LAND_START item). A vehicle that is using missions for landing (e.g. in a return mode) will join the mission on the closest path of the return-path segment (instead of MAV_CMD_DO_LAND_START or the nearest waypoint). The main use case is to minimize the failsafe flight path in corridor missions, where the inbound/outbound paths are constrained (by geofences) to the same particular path. The MAV_CMD_NAV_RETURN_PATH_START would be placed at the start of the return path. If a failsafe occurs on the outbound path the vehicle will move to the nearest point on the return path (which is parallel for this kind of mission), effectively turning round and following the shortest path to landing. If a failsafe occurs on the inbound path the vehicle is already on the return segment and will continue to landing. The Latitude/Longitude/Altitude are optional, and may be set to 0 if not needed. If specified, the item defines the waypoint at which the return segment starts. If sent using as a command, the vehicle will perform a mission landing (using the land segment if defined) or reject the command if mission landings are not supported, or no mission landing is defined. When used as a command any position information in the command is ignored."]
1975 #[doc = ""]
1976 #[doc = "# Parameters"]
1977 #[doc = ""]
1978 #[doc = "| Parameter | Description | Units |"]
1979 #[doc = "| --------- | ----------- | ----- |"]
1980 #[doc = "| 1 | Empty | |"]
1981 #[doc = "| 2 | Empty | |"]
1982 #[doc = "| 3 | Empty | |"]
1983 #[doc = "| 4 | Empty | |"]
1984 #[doc = "| 5 (Latitude)| Latitudee. 0: not used.| |"]
1985 #[doc = "| 6 (Longitude)| Longitudee. 0: not used.| |"]
1986 #[doc = "| 7 (Altitude)| Altitudee. 0: not used.| m |"]
1987 MAV_CMD_DO_RETURN_PATH_START = 188,
1988 #[doc = "Mission item to mark the start of a mission landing pattern, or a command to land with a mission landing pattern. When used in a mission, this is a marker for the start of a sequence of mission items that represent a landing pattern. It should be followed by a navigation item that defines the first waypoint of the landing sequence. The start marker positional params are used only for selecting what landing pattern to use if several are defined in the mission (the selected pattern will be the one with the marker position that is closest to the vehicle when a landing is commanded). If the marker item position has zero-values for latitude, longitude, and altitude, then landing pattern selection is instead based on the position of the first waypoint in the landing sequence. \t When sent as a command it triggers a landing using a mission landing pattern. \t The location parameters are not used in this case, and should be set to 0."]
1989 #[doc = ""]
1990 #[doc = "# Parameters"]
1991 #[doc = ""]
1992 #[doc = "| Parameter | Description | Units |"]
1993 #[doc = "| --------- | ----------- | ----- |"]
1994 #[doc = "| 1 | Empty | |"]
1995 #[doc = "| 2 | Empty | |"]
1996 #[doc = "| 3 | Empty | |"]
1997 #[doc = "| 4 | Empty | |"]
1998 #[doc = "| 5 (Latitude)| Latitude for landing sequence selection, or 0 (see description). Ignored in commands (set 0).| |"]
1999 #[doc = "| 6 (Longitude)| Longitude for landing sequence selection, or 0 (see description). Ignored in commands (set 0).| |"]
2000 #[doc = "| 7 (Altitude)| Altitude for landing sequence selection, or 0 (see description). Ignored in commands (set 0).| m |"]
2001 MAV_CMD_DO_LAND_START = 189,
2002 #[doc = "Mission command to perform a landing from a rally point."]
2003 #[doc = ""]
2004 #[doc = "# Parameters"]
2005 #[doc = ""]
2006 #[doc = "| Parameter | Description | Units |"]
2007 #[doc = "| --------- | ----------- | ----- |"]
2008 #[doc = "| 1 (Altitude)| Break altitude| m |"]
2009 #[doc = "| 2 (Speed) | Landing speed| m/s |"]
2010 #[doc = "| 3 | Empty | |"]
2011 #[doc = "| 4 | Empty | |"]
2012 #[doc = "| 5 | Empty | |"]
2013 #[doc = "| 6 | Empty | |"]
2014 #[doc = "| 7 | Empty | |"]
2015 MAV_CMD_DO_RALLY_LAND = 190,
2016 #[doc = "Mission command to safely abort an autonomous landing."]
2017 #[doc = ""]
2018 #[doc = "# Parameters"]
2019 #[doc = ""]
2020 #[doc = "| Parameter | Description | Units |"]
2021 #[doc = "| --------- | ----------- | ----- |"]
2022 #[doc = "| 1 (Altitude)| Altitude | m |"]
2023 #[doc = "| 2 | Empty | |"]
2024 #[doc = "| 3 | Empty | |"]
2025 #[doc = "| 4 | Empty | |"]
2026 #[doc = "| 5 | Empty | |"]
2027 #[doc = "| 6 | Empty | |"]
2028 #[doc = "| 7 | Empty | |"]
2029 MAV_CMD_DO_GO_AROUND = 191,
2030 #[doc = "Reposition the vehicle to a specific WGS84 global position. This command is intended for guided commands (for missions use MAV_CMD_NAV_WAYPOINT instead)."]
2031 #[doc = ""]
2032 #[doc = "# Parameters"]
2033 #[doc = ""]
2034 #[doc = "| Parameter | Description | Values | Units |"]
2035 #[doc = "| --------- | ----------- | ------ | ----- |"]
2036 #[doc = "| 1 (Speed) | Ground speed, less than 0 (-1) for default| ≥ -1 | m/s |"]
2037 #[doc = "| 2 (Bitmask)| Bitmask of option flags.| [`MavDoRepositionFlags`] | |"]
2038 #[doc = "| 3 (Radius)| Loiter radius for planes. Positive values only, direction is controlled by Yaw value. A value of zero or NaN is ignored.| | m |"]
2039 #[doc = "| 4 (Yaw) | Yaw heading. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.). For planes indicates loiter direction (0: clockwise, 1: counter clockwise)| | rad |"]
2040 #[doc = "| 5 (Latitude)| Latitude | | |"]
2041 #[doc = "| 6 (Longitude)| Longitude | | |"]
2042 #[doc = "| 7 (Altitude)| Altitude | | m |"]
2043 MAV_CMD_DO_REPOSITION = 192,
2044 #[doc = "If in a GPS controlled position mode, hold the current position or continue."]
2045 #[doc = ""]
2046 #[doc = "# Parameters"]
2047 #[doc = ""]
2048 #[doc = "| Parameter | Description | Values |"]
2049 #[doc = "| --------- | ----------- | ------ |"]
2050 #[doc = "| 1 (Continue)| 0: Pause current mission or reposition command, hold current position. 1: Continue mission. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius.| 0, 1 |"]
2051 #[doc = "| 2 | Reserved | |"]
2052 #[doc = "| 3 | Reserved | |"]
2053 #[doc = "| 4 | Reserved | |"]
2054 #[doc = "| 5 | Reserved | |"]
2055 #[doc = "| 6 | Reserved | |"]
2056 #[doc = "| 7 | Reserved | |"]
2057 MAV_CMD_DO_PAUSE_CONTINUE = 193,
2058 #[doc = "Set moving direction to forward or reverse."]
2059 #[doc = ""]
2060 #[doc = "# Parameters"]
2061 #[doc = ""]
2062 #[doc = "| Parameter | Description | Values |"]
2063 #[doc = "| --------- | ----------- | ------ |"]
2064 #[doc = "| 1 (Reverse)| Direction (0=Forward, 1=Reverse)| 0, 1 |"]
2065 #[doc = "| 2 | Empty | |"]
2066 #[doc = "| 3 | Empty | |"]
2067 #[doc = "| 4 | Empty | |"]
2068 #[doc = "| 5 | Empty | |"]
2069 #[doc = "| 6 | Empty | |"]
2070 #[doc = "| 7 | Empty | |"]
2071 MAV_CMD_DO_SET_REVERSE = 194,
2072 #[doc = "Sets the region of interest (ROI) to a location. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal is not to react to this message."]
2073 #[doc = ""]
2074 #[doc = "# Parameters"]
2075 #[doc = ""]
2076 #[doc = "| Parameter | Description | Units |"]
2077 #[doc = "| --------- | ----------- | ----- |"]
2078 #[doc = "| 1 (Gimbal device ID)| Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).| |"]
2079 #[doc = "| 2 | Empty | |"]
2080 #[doc = "| 3 | Empty | |"]
2081 #[doc = "| 4 | Empty | |"]
2082 #[doc = "| 5 (Latitude)| Latitude of ROI location| degE7 |"]
2083 #[doc = "| 6 (Longitude)| Longitude of ROI location| degE7 |"]
2084 #[doc = "| 7 (Altitude)| Altitude of ROI location| m |"]
2085 MAV_CMD_DO_SET_ROI_LOCATION = 195,
2086 #[doc = "Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message."]
2087 #[doc = ""]
2088 #[doc = "# Parameters"]
2089 #[doc = ""]
2090 #[doc = "| Parameter | Description | Units |"]
2091 #[doc = "| --------- | ----------- | ----- |"]
2092 #[doc = "| 1 (Gimbal device ID)| Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).| |"]
2093 #[doc = "| 2 | Empty | |"]
2094 #[doc = "| 3 | Empty | |"]
2095 #[doc = "| 4 | Empty | |"]
2096 #[doc = "| 5 (Pitch Offset)| Pitch offset from next waypoint, positive pitching up| deg |"]
2097 #[doc = "| 6 (Roll Offset)| Roll offset from next waypoint, positive rolling to the right| deg |"]
2098 #[doc = "| 7 (Yaw Offset)| Yaw offset from next waypoint, positive yawing to the right| deg |"]
2099 MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET = 196,
2100 #[doc = "Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message. After this command the gimbal manager should go back to manual input if available, and otherwise assume a neutral position."]
2101 #[doc = ""]
2102 #[doc = "# Parameters"]
2103 #[doc = ""]
2104 #[doc = "| Parameter | Description |"]
2105 #[doc = "| --------- | ----------- |"]
2106 #[doc = "| 1 (Gimbal device ID)| Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).|"]
2107 #[doc = "| 2 | Empty |"]
2108 #[doc = "| 3 | Empty |"]
2109 #[doc = "| 4 | Empty |"]
2110 #[doc = "| 5 | Empty |"]
2111 #[doc = "| 6 | Empty |"]
2112 #[doc = "| 7 | Empty |"]
2113 MAV_CMD_DO_SET_ROI_NONE = 197,
2114 #[doc = "Mount tracks system with specified system ID. Determination of target vehicle position may be done with GLOBAL_POSITION_INT or any other means. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message."]
2115 #[doc = ""]
2116 #[doc = "# Parameters"]
2117 #[doc = ""]
2118 #[doc = "| Parameter | Description | Values |"]
2119 #[doc = "| --------- | ----------- | ------ |"]
2120 #[doc = "| 1 (System ID)| System ID | 1, 2, .. , 255 |"]
2121 #[doc = "| 2 (Gimbal device ID)| Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).| |"]
2122 MAV_CMD_DO_SET_ROI_SYSID = 198,
2123 #[doc = "Control onboard camera system."]
2124 #[doc = ""]
2125 #[doc = "# Parameters"]
2126 #[doc = ""]
2127 #[doc = "| Parameter | Description | Values | Units |"]
2128 #[doc = "| --------- | ----------- | ------ | ----- |"]
2129 #[doc = "| 1 (ID) | Camera ID (-1 for all)| -1, 0, .. | |"]
2130 #[doc = "| 2 (Transmission)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| 0, 1, 2 | |"]
2131 #[doc = "| 3 (Interval)| Transmission mode: 0: video stream,>0: single images every n seconds| ≥ 0 | s |"]
2132 #[doc = "| 4 (Recording)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| 0, 1, 2 | |"]
2133 #[doc = "| 5 | Empty | | |"]
2134 #[doc = "| 6 | Empty | | |"]
2135 #[doc = "| 7 | Empty | | |"]
2136 MAV_CMD_DO_CONTROL_VIDEO = 200,
2137 #[deprecated = " See `MAV_CMD_DO_SET_ROI_*` (Deprecated since 2018-01)"]
2138 #[doc = "Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras."]
2139 #[doc = ""]
2140 #[doc = "# Parameters"]
2141 #[doc = ""]
2142 #[doc = "| Parameter | Description | Values |"]
2143 #[doc = "| --------- | ----------- | ------ |"]
2144 #[doc = "| 1 (ROI Mode)| Region of interest mode.| [`MavRoi`] |"]
2145 #[doc = "| 2 (WP Index)| Waypoint index/ target ID (depends on param 1).| 0, 1, .. |"]
2146 #[doc = "| 3 (ROI Index)| Region of interest index. (allows a vehicle to manage multiple ROI's)| 0, 1, .. |"]
2147 #[doc = "| 4 | Empty | |"]
2148 #[doc = "| 5 | MAV_ROI_WPNEXT: pitch offset from next waypoint, MAV_ROI_LOCATION: latitude| |"]
2149 #[doc = "| 6 | MAV_ROI_WPNEXT: roll offset from next waypoint, MAV_ROI_LOCATION: longitude| |"]
2150 #[doc = "| 7 | MAV_ROI_WPNEXT: yaw offset from next waypoint, MAV_ROI_LOCATION: altitude| |"]
2151 MAV_CMD_DO_SET_ROI = 201,
2152 #[doc = "Configure digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see <https://mavlink.io/en/services/camera_def.html> )."]
2153 #[doc = ""]
2154 #[doc = "# Parameters"]
2155 #[doc = ""]
2156 #[doc = "| Parameter | Description | Values | Units |"]
2157 #[doc = "| --------- | ----------- | ------ | ----- |"]
2158 #[doc = "| 1 (Mode) | Modes: P, TV, AV, M, Etc.| 0, 1, .. | |"]
2159 #[doc = "| 2 (Shutter Speed)| Shutter speed: Divisor number for one second.| 0, 1, .. | |"]
2160 #[doc = "| 3 (Aperture)| Aperture: F stop number.| ≥ 0 | |"]
2161 #[doc = "| 4 (ISO) | ISO number e.g. 80, 100, 200, Etc.| 0, 1, .. | |"]
2162 #[doc = "| 5 (Exposure)| Exposure type enumerator.| | |"]
2163 #[doc = "| 6 (Command Identity)| Command Identity.| | |"]
2164 #[doc = "| 7 (Engine Cut-off)| Main engine cut-off time before camera trigger. (0 means no cut-off)| 0, 1, .. | ds |"]
2165 MAV_CMD_DO_DIGICAM_CONFIGURE = 202,
2166 #[doc = "Control digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see <https://mavlink.io/en/services/camera_def.html> )."]
2167 #[doc = ""]
2168 #[doc = "# Parameters"]
2169 #[doc = ""]
2170 #[doc = "| Parameter | Description |"]
2171 #[doc = "| --------- | ----------- |"]
2172 #[doc = "| 1 (Session Control)| Session control e.g. show/hide lens|"]
2173 #[doc = "| 2 (Zoom Absolute)| Zoom's absolute position|"]
2174 #[doc = "| 3 (Zoom Relative)| Zooming step value to offset zoom from the current position|"]
2175 #[doc = "| 4 (Focus) | Focus Locking, Unlocking or Re-locking|"]
2176 #[doc = "| 5 (Shoot Command)| Shooting Command|"]
2177 #[doc = "| 6 (Command Identity)| Command Identity|"]
2178 #[doc = "| 7 (Shot ID)| Test shot identifier. If set to 1, image will only be captured, but not counted towards internal frame count.|"]
2179 MAV_CMD_DO_DIGICAM_CONTROL = 203,
2180 #[deprecated = "This message has been superseded by MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE. The message can still be used to communicate with legacy gimbals implementing it. See `MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE` (Deprecated since 2020-01)"]
2181 #[doc = "Mission command to configure a camera or antenna mount"]
2182 #[doc = ""]
2183 #[doc = "# Parameters"]
2184 #[doc = ""]
2185 #[doc = "| Parameter | Description | Values |"]
2186 #[doc = "| --------- | ----------- | ------ |"]
2187 #[doc = "| 1 (Mode) | Mount operation mode| [`MavMountMode`] |"]
2188 #[doc = "| 2 (Stabilize Roll)| stabilize roll? (1 = yes, 0 = no)| 0, 1 |"]
2189 #[doc = "| 3 (Stabilize Pitch)| stabilize pitch? (1 = yes, 0 = no)| 0, 1 |"]
2190 #[doc = "| 4 (Stabilize Yaw)| stabilize yaw? (1 = yes, 0 = no)| 0, 1 |"]
2191 #[doc = "| 5 (Roll Input Mode)| roll input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame)| |"]
2192 #[doc = "| 6 (Pitch Input Mode)| pitch input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame)| |"]
2193 #[doc = "| 7 (Yaw Input Mode)| yaw input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame)| |"]
2194 MAV_CMD_DO_MOUNT_CONFIGURE = 204,
2195 #[deprecated = "This message is ambiguous and inconsistent. It has been superseded by MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW and `MAV_CMD_DO_SET_ROI_*` variants. The message can still be used to communicate with legacy gimbals implementing it. See `MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW` (Deprecated since 2020-01)"]
2196 #[doc = "Mission command to control a camera or antenna mount"]
2197 #[doc = ""]
2198 #[doc = "# Parameters"]
2199 #[doc = ""]
2200 #[doc = "| Parameter | Description | Values | Units |"]
2201 #[doc = "| --------- | ----------- | ------ | ----- |"]
2202 #[doc = "| 1 (Pitch) | pitch depending on mount mode (degrees or degrees/second depending on pitch input).| | |"]
2203 #[doc = "| 2 (Roll) | roll depending on mount mode (degrees or degrees/second depending on roll input).| | |"]
2204 #[doc = "| 3 (Yaw) | yaw depending on mount mode (degrees or degrees/second depending on yaw input).| | |"]
2205 #[doc = "| 4 (Altitude)| altitude depending on mount mode.| | m |"]
2206 #[doc = "| 5 (Latitude)| latitude, set if appropriate mount mode.| | |"]
2207 #[doc = "| 6 (Longitude)| longitude, set if appropriate mount mode.| | |"]
2208 #[doc = "| 7 (Mode) | Mount mode. | [`MavMountMode`] | |"]
2209 MAV_CMD_DO_MOUNT_CONTROL = 205,
2210 #[doc = "Mission command to set camera trigger distance for this flight. The camera is triggered each time this distance is exceeded. This command can also be used to set the shutter integration time for the camera."]
2211 #[doc = ""]
2212 #[doc = "# Parameters"]
2213 #[doc = ""]
2214 #[doc = "| Parameter | Description | Values | Units |"]
2215 #[doc = "| --------- | ----------- | ------ | ----- |"]
2216 #[doc = "| 1 (Distance)| Camera trigger distance. 0 to stop triggering.| ≥ 0 | m |"]
2217 #[doc = "| 2 (Shutter)| Camera shutter integration time. -1 or 0 to ignore| -1, 0, .. | ms |"]
2218 #[doc = "| 3 (Trigger)| Trigger camera once immediately. (0 = no trigger, 1 = trigger)| 0, 1 | |"]
2219 #[doc = "| 4 (Target Camera ID)| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| 0, 1, .. , 255 | |"]
2220 #[doc = "| 5 | Empty | | |"]
2221 #[doc = "| 6 | Empty | | |"]
2222 #[doc = "| 7 | Empty | | |"]
2223 MAV_CMD_DO_SET_CAM_TRIGG_DIST = 206,
2224 #[doc = "Enable the geofence. This can be used in a mission or via the command protocol. The persistence/lifetime of the setting is undefined. Depending on flight stack implementation it may persist until superseded, or it may revert to a system default at the end of a mission. Flight stacks typically reset the setting to system defaults on reboot."]
2225 #[doc = ""]
2226 #[doc = "# Parameters"]
2227 #[doc = ""]
2228 #[doc = "| Parameter | Description | Values |"]
2229 #[doc = "| --------- | ----------- | ------ |"]
2230 #[doc = "| 1 (Enable)| enable? (0=disable, 1=enable, 2=disable_floor_only)| 0, 1, 2 |"]
2231 #[doc = "| 2 (Types) | Fence types to enable or disable as a bitmask. 0: field is unused/all fences should be enabled or disabled (for compatiblity reasons). Parameter is ignored if param1=2.| [`FenceType`] |"]
2232 #[doc = "| 3 | Empty | |"]
2233 #[doc = "| 4 | Empty | |"]
2234 #[doc = "| 5 | Empty | |"]
2235 #[doc = "| 6 | Empty | |"]
2236 #[doc = "| 7 | Empty | |"]
2237 MAV_CMD_DO_FENCE_ENABLE = 207,
2238 #[doc = "Mission item/command to release a parachute or enable/disable auto release."]
2239 #[doc = ""]
2240 #[doc = "# Parameters"]
2241 #[doc = ""]
2242 #[doc = "| Parameter | Description | Values |"]
2243 #[doc = "| --------- | ----------- | ------ |"]
2244 #[doc = "| 1 (Action)| Action | [`ParachuteAction`] |"]
2245 #[doc = "| 2 | Empty | |"]
2246 #[doc = "| 3 | Empty | |"]
2247 #[doc = "| 4 | Empty | |"]
2248 #[doc = "| 5 | Empty | |"]
2249 #[doc = "| 6 | Empty | |"]
2250 #[doc = "| 7 | Empty | |"]
2251 MAV_CMD_DO_PARACHUTE = 208,
2252 #[doc = "Command to perform motor test."]
2253 #[doc = ""]
2254 #[doc = "# Parameters"]
2255 #[doc = ""]
2256 #[doc = "| Parameter | Description | Values | Units |"]
2257 #[doc = "| --------- | ----------- | ------ | ----- |"]
2258 #[doc = "| 1 (Instance)| Motor instance number (from 1 to max number of motors on the vehicle).| 1, 2, .. | |"]
2259 #[doc = "| 2 (Throttle Type)| Throttle type (whether the Throttle Value in param3 is a percentage, PWM value, etc.)| [`MotorTestThrottleType`] | |"]
2260 #[doc = "| 3 (Throttle)| Throttle value.| | |"]
2261 #[doc = "| 4 (Timeout)| Timeout between tests that are run in sequence.| ≥ 0 | s |"]
2262 #[doc = "| 5 (Motor Count)| Motor count. Number of motors to test in sequence: 0/1=one motor, 2= two motors, etc. The Timeout (param4) is used between tests.| 0, 1, .. | |"]
2263 #[doc = "| 6 (Test Order)| Motor test order.| [`MotorTestOrder`] | |"]
2264 #[doc = "| 7 | Empty | | |"]
2265 MAV_CMD_DO_MOTOR_TEST = 209,
2266 #[doc = "Change to/from inverted flight."]
2267 #[doc = ""]
2268 #[doc = "# Parameters"]
2269 #[doc = ""]
2270 #[doc = "| Parameter | Description | Values |"]
2271 #[doc = "| --------- | ----------- | ------ |"]
2272 #[doc = "| 1 (Inverted)| Inverted flight. (0=normal, 1=inverted)| 0, 1 |"]
2273 #[doc = "| 2 | Empty | |"]
2274 #[doc = "| 3 | Empty | |"]
2275 #[doc = "| 4 | Empty | |"]
2276 #[doc = "| 5 | Empty | |"]
2277 #[doc = "| 6 | Empty | |"]
2278 #[doc = "| 7 | Empty | |"]
2279 MAV_CMD_DO_INVERTED_FLIGHT = 210,
2280 #[doc = "Mission command to operate a gripper."]
2281 #[doc = ""]
2282 #[doc = "# Parameters"]
2283 #[doc = ""]
2284 #[doc = "| Parameter | Description | Values |"]
2285 #[doc = "| --------- | ----------- | ------ |"]
2286 #[doc = "| 1 (Instance)| Gripper instance number.| 1, 2, .. |"]
2287 #[doc = "| 2 (Action)| Gripper action to perform.| [`GripperActions`] |"]
2288 #[doc = "| 3 | Empty | |"]
2289 #[doc = "| 4 | Empty | |"]
2290 #[doc = "| 5 | Empty | |"]
2291 #[doc = "| 6 | Empty | |"]
2292 #[doc = "| 7 | Empty | |"]
2293 MAV_CMD_DO_GRIPPER = 211,
2294 #[doc = "Enable/disable autotune."]
2295 #[doc = ""]
2296 #[doc = "# Parameters"]
2297 #[doc = ""]
2298 #[doc = "| Parameter | Description | Values |"]
2299 #[doc = "| --------- | ----------- | ------ |"]
2300 #[doc = "| 1 (Enable)| Enable (1: enable, 0:disable).| 0, 1 |"]
2301 #[doc = "| 2 (Axis) | Specify axes for which autotuning is enabled/disabled. 0 indicates the field is unused (for compatiblity reasons). If 0 the autopilot will follow its default behaviour, which is usually to tune all axes.| [`AutotuneAxis`] |"]
2302 #[doc = "| 3 | Empty. | |"]
2303 #[doc = "| 4 | Empty. | |"]
2304 #[doc = "| 5 | Empty. | |"]
2305 #[doc = "| 6 | Empty. | |"]
2306 #[doc = "| 7 | Empty. | |"]
2307 MAV_CMD_DO_AUTOTUNE_ENABLE = 212,
2308 #[doc = "Sets a desired vehicle turn angle and speed change."]
2309 #[doc = ""]
2310 #[doc = "# Parameters"]
2311 #[doc = ""]
2312 #[doc = "| Parameter | Description | Values | Units |"]
2313 #[doc = "| --------- | ----------- | ------ | ----- |"]
2314 #[doc = "| 1 (Yaw) | Yaw angle to adjust steering by.| | deg |"]
2315 #[doc = "| 2 (Speed) | Speed. | | m/s |"]
2316 #[doc = "| 3 (Angle) | Final angle. (0=absolute, 1=relative)| 0, 1 | |"]
2317 #[doc = "| 4 | Empty | | |"]
2318 #[doc = "| 5 | Empty | | |"]
2319 #[doc = "| 6 | Empty | | |"]
2320 #[doc = "| 7 | Empty | | |"]
2321 MAV_CMD_NAV_SET_YAW_SPEED = 213,
2322 #[doc = "Mission command to set camera trigger interval for this flight. If triggering is enabled, the camera is triggered each time this interval expires. This command can also be used to set the shutter integration time for the camera."]
2323 #[doc = ""]
2324 #[doc = "# Parameters"]
2325 #[doc = ""]
2326 #[doc = "| Parameter | Description | Values | Units |"]
2327 #[doc = "| --------- | ----------- | ------ | ----- |"]
2328 #[doc = "| 1 (Trigger Cycle)| Camera trigger cycle time. -1 or 0 to ignore.| -1, 0, .. | ms |"]
2329 #[doc = "| 2 (Shutter Integration)| Camera shutter integration time. Should be less than trigger cycle time. -1 or 0 to ignore.| -1, 0, .. | ms |"]
2330 #[doc = "| 3 (Target Camera ID)| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| 0, 1, .. , 255 | |"]
2331 #[doc = "| 4 | Empty | | |"]
2332 #[doc = "| 5 | Empty | | |"]
2333 #[doc = "| 6 | Empty | | |"]
2334 #[doc = "| 7 | Empty | | |"]
2335 MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL = 214,
2336 #[deprecated = " See `MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW` (Deprecated since 2020-01)"]
2337 #[doc = "Mission command to control a camera or antenna mount, using a quaternion as reference."]
2338 #[doc = ""]
2339 #[doc = "# Parameters"]
2340 #[doc = ""]
2341 #[doc = "| Parameter | Description |"]
2342 #[doc = "| --------- | ----------- |"]
2343 #[doc = "| 1 (Q1) | quaternion param q1, w (1 in null-rotation)|"]
2344 #[doc = "| 2 (Q2) | quaternion param q2, x (0 in null-rotation)|"]
2345 #[doc = "| 3 (Q3) | quaternion param q3, y (0 in null-rotation)|"]
2346 #[doc = "| 4 (Q4) | quaternion param q4, z (0 in null-rotation)|"]
2347 #[doc = "| 5 | Empty |"]
2348 #[doc = "| 6 | Empty |"]
2349 #[doc = "| 7 | Empty |"]
2350 MAV_CMD_DO_MOUNT_CONTROL_QUAT = 220,
2351 #[doc = "set id of master controller"]
2352 #[doc = ""]
2353 #[doc = "# Parameters"]
2354 #[doc = ""]
2355 #[doc = "| Parameter | Description | Values |"]
2356 #[doc = "| --------- | ----------- | ------ |"]
2357 #[doc = "| 1 (System ID)| System ID | 0, 1, .. , 255 |"]
2358 #[doc = "| 2 (Component ID)| Component ID| 0, 1, .. , 255 |"]
2359 #[doc = "| 3 | Empty | |"]
2360 #[doc = "| 4 | Empty | |"]
2361 #[doc = "| 5 | Empty | |"]
2362 #[doc = "| 6 | Empty | |"]
2363 #[doc = "| 7 | Empty | |"]
2364 MAV_CMD_DO_GUIDED_MASTER = 221,
2365 #[doc = "Set limits for external control"]
2366 #[doc = ""]
2367 #[doc = "# Parameters"]
2368 #[doc = ""]
2369 #[doc = "| Parameter | Description | Values | Units |"]
2370 #[doc = "| --------- | ----------- | ------ | ----- |"]
2371 #[doc = "| 1 (Timeout)| Timeout - maximum time that external controller will be allowed to control vehicle. 0 means no timeout.| ≥ 0 | s |"]
2372 #[doc = "| 2 (Min Altitude)| Altitude (MSL) min - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit.| | m |"]
2373 #[doc = "| 3 (Max Altitude)| Altitude (MSL) max - if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit.| | m |"]
2374 #[doc = "| 4 (Horiz. Move Limit)| Horizontal move limit - if vehicle moves more than this distance from its location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal move limit.| ≥ 0 | m |"]
2375 #[doc = "| 5 | Empty | | |"]
2376 #[doc = "| 6 | Empty | | |"]
2377 #[doc = "| 7 | Empty | | |"]
2378 MAV_CMD_DO_GUIDED_LIMITS = 222,
2379 #[doc = "Control vehicle engine. This is interpreted by the vehicles engine controller to change the target engine state. It is intended for vehicles with internal combustion engines"]
2380 #[doc = ""]
2381 #[doc = "# Parameters"]
2382 #[doc = ""]
2383 #[doc = "| Parameter | Description | Values | Units |"]
2384 #[doc = "| --------- | ----------- | ------ | ----- |"]
2385 #[doc = "| 1 (Start Engine)| 0: Stop engine, 1:Start Engine| 0, 1 | |"]
2386 #[doc = "| 2 (Cold Start)| 0: Warm start, 1:Cold start. Controls use of choke where applicable| 0, 1 | |"]
2387 #[doc = "| 3 (Height Delay)| Height delay. This is for commanding engine start only after the vehicle has gained the specified height. Used in VTOL vehicles during takeoff to start engine after the aircraft is off the ground. Zero for no delay.| ≥ 0 | m |"]
2388 #[doc = "| 4 | Empty | | |"]
2389 #[doc = "| 5 | Empty | | |"]
2390 #[doc = "| 6 | Empty | | |"]
2391 #[doc = "| 7 | Empty | | |"]
2392 MAV_CMD_DO_ENGINE_CONTROL = 223,
2393 #[doc = "Set the mission item with sequence number seq as the current item and emit MISSION_CURRENT (whether or not the mission number changed). If a mission is currently being executed, the system will continue to this new mission item on the shortest path, skipping any intermediate mission items. \t Note that mission jump repeat counters are not reset unless param2 is set (see MAV_CMD_DO_JUMP param2). This command may trigger a mission state-machine change on some systems: for example from MISSION_STATE_NOT_STARTED or MISSION_STATE_PAUSED to MISSION_STATE_ACTIVE. If the system is in mission mode, on those systems this command might therefore start, restart or resume the mission. If the system is not in mission mode this command must not trigger a switch to mission mode. The mission may be \"reset\" using param2. Resetting sets jump counters to initial values (to reset counters without changing the current mission item set the param1 to `-1`). Resetting also explicitly changes a mission state of MISSION_STATE_COMPLETE to MISSION_STATE_PAUSED or MISSION_STATE_ACTIVE, potentially allowing it to resume when it is (next) in a mission mode. \t The command will ACK with MAV_RESULT_FAILED if the sequence number is out of range (including if there is no mission item)."]
2394 #[doc = ""]
2395 #[doc = "# Parameters"]
2396 #[doc = ""]
2397 #[doc = "| Parameter | Description | Values |"]
2398 #[doc = "| --------- | ----------- | ------ |"]
2399 #[doc = "| 1 (Number)| Mission sequence value to set. -1 for the current mission item (use to reset mission without changing current mission item).| -1, 0, .. |"]
2400 #[doc = "| 2 (Reset Mission)| Resets mission. 1: true, 0: false. Resets jump counters to initial values and changes mission state \"completed\" to be \"active\" or \"paused\".| 0, 1 |"]
2401 #[doc = "| 3 | Empty | |"]
2402 #[doc = "| 4 | Empty | |"]
2403 #[doc = "| 5 | Empty | |"]
2404 #[doc = "| 6 | Empty | |"]
2405 #[doc = "| 7 | Empty | |"]
2406 MAV_CMD_DO_SET_MISSION_CURRENT = 224,
2407 #[doc = "NOP - This command is only used to mark the upper limit of the DO commands in the enumeration"]
2408 #[doc = ""]
2409 #[doc = "# Parameters"]
2410 #[doc = ""]
2411 #[doc = "| Parameter | Description |"]
2412 #[doc = "| --------- | ----------- |"]
2413 #[doc = "| 1 | Empty |"]
2414 #[doc = "| 2 | Empty |"]
2415 #[doc = "| 3 | Empty |"]
2416 #[doc = "| 4 | Empty |"]
2417 #[doc = "| 5 | Empty |"]
2418 #[doc = "| 6 | Empty |"]
2419 #[doc = "| 7 | Empty |"]
2420 MAV_CMD_DO_LAST = 240,
2421 #[doc = "Trigger calibration. This command will be only accepted if in pre-flight mode. Except for Temperature Calibration, only one sensor should be set in a single message and all others should be zero."]
2422 #[doc = ""]
2423 #[doc = "# Parameters"]
2424 #[doc = ""]
2425 #[doc = "| Parameter | Description | Values |"]
2426 #[doc = "| --------- | ----------- | ------ |"]
2427 #[doc = "| 1 (Gyro Temperature)| 1: gyro calibration, 3: gyro temperature calibration| 0, 1, .. , 3 |"]
2428 #[doc = "| 2 (Magnetometer)| 1: magnetometer calibration| 0, 1 |"]
2429 #[doc = "| 3 (Ground Pressure)| 1: ground pressure calibration| 0, 1 |"]
2430 #[doc = "| 4 (Remote Control)| 1: radio RC calibration, 2: RC trim calibration| 0, 1 |"]
2431 #[doc = "| 5 (Accelerometer)| 1: accelerometer calibration, 2: board level calibration, 3: accelerometer temperature calibration, 4: simple accelerometer calibration| 0, 1, .. , 4 |"]
2432 #[doc = "| 6 (Compmot or Airspeed)| 1: APM: compass/motor interference calibration (PX4: airspeed calibration, deprecated), 2: airspeed calibration| 0, 1, 2 |"]
2433 #[doc = "| 7 (ESC or Baro)| 1: ESC calibration, 3: barometer temperature calibration| 0, 1, .. , 3 |"]
2434 MAV_CMD_PREFLIGHT_CALIBRATION = 241,
2435 #[doc = "Set sensor offsets. This command will be only accepted if in pre-flight mode."]
2436 #[doc = ""]
2437 #[doc = "# Parameters"]
2438 #[doc = ""]
2439 #[doc = "| Parameter | Description | Values |"]
2440 #[doc = "| --------- | ----------- | ------ |"]
2441 #[doc = "| 1 (Sensor Type)| Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer, 6: third magnetometer| 0, 1, .. , 6 |"]
2442 #[doc = "| 2 (X Offset)| X axis offset (or generic dimension 1), in the sensor's raw units| |"]
2443 #[doc = "| 3 (Y Offset)| Y axis offset (or generic dimension 2), in the sensor's raw units| |"]
2444 #[doc = "| 4 (Z Offset)| Z axis offset (or generic dimension 3), in the sensor's raw units| |"]
2445 #[doc = "| 5 (4th Dimension)| Generic dimension 4, in the sensor's raw units| |"]
2446 #[doc = "| 6 (5th Dimension)| Generic dimension 5, in the sensor's raw units| |"]
2447 #[doc = "| 7 (6th Dimension)| Generic dimension 6, in the sensor's raw units| |"]
2448 MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242,
2449 #[doc = "Trigger UAVCAN configuration (actuator ID assignment and direction mapping). Note that this maps to the legacy UAVCAN v0 function UAVCAN_ENUMERATE, which is intended to be executed just once during initial vehicle configuration (it is not a normal pre-flight command and has been poorly named)."]
2450 #[doc = ""]
2451 #[doc = "# Parameters"]
2452 #[doc = ""]
2453 #[doc = "| Parameter | Description |"]
2454 #[doc = "| --------- | ----------- |"]
2455 #[doc = "| 1 (Actuator ID)| 1: Trigger actuator ID assignment and direction mapping. 0: Cancel command.|"]
2456 #[doc = "| 2 | Reserved |"]
2457 #[doc = "| 3 | Reserved |"]
2458 #[doc = "| 4 | Reserved |"]
2459 #[doc = "| 5 | Reserved |"]
2460 #[doc = "| 6 | Reserved |"]
2461 #[doc = "| 7 | Reserved |"]
2462 MAV_CMD_PREFLIGHT_UAVCAN = 243,
2463 #[doc = "Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode."]
2464 #[doc = ""]
2465 #[doc = "# Parameters"]
2466 #[doc = ""]
2467 #[doc = "| Parameter | Description | Values | Units |"]
2468 #[doc = "| --------- | ----------- | ------ | ----- |"]
2469 #[doc = "| 1 (Parameter Storage)| Action to perform on the persistent parameter storage| [`PreflightStorageParameterAction`] | |"]
2470 #[doc = "| 2 (Mission Storage)| Action to perform on the persistent mission storage| [`PreflightStorageMissionAction`] | |"]
2471 #[doc = "| 3 (Logging Rate)| Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging,>1: logging rate (e.g. set to 1000 for 1000 Hz logging)| -1, 0, .. | Hz |"]
2472 #[doc = "| 4 | Reserved | | |"]
2473 #[doc = "| 5 | Empty | | |"]
2474 #[doc = "| 6 | Empty | | |"]
2475 #[doc = "| 7 | Empty | | |"]
2476 MAV_CMD_PREFLIGHT_STORAGE = 245,
2477 #[doc = "Request the reboot or shutdown of system components."]
2478 #[doc = ""]
2479 #[doc = "# Parameters"]
2480 #[doc = ""]
2481 #[doc = "| Parameter | Description | Values |"]
2482 #[doc = "| --------- | ----------- | ------ |"]
2483 #[doc = "| 1 (Autopilot)| 0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded.| 0, 1, .. , 3 |"]
2484 #[doc = "| 2 (Companion)| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded.| 0, 1, .. , 3 |"]
2485 #[doc = "| 3 (Component action)| 0: Do nothing for component, 1: Reboot component, 2: Shutdown component, 3: Reboot component and keep it in the bootloader until upgraded| 0, 1, .. , 3 |"]
2486 #[doc = "| 4 (Component ID)| MAVLink Component ID targeted in param3 (0 for all components).| 0, 1, .. , 255 |"]
2487 #[doc = "| 5 | Reserved (set to 0)| |"]
2488 #[doc = "| 6 (Conditions)| Conditions under which reboot/shutdown is allowed.| [`RebootShutdownConditions`] |"]
2489 #[doc = "| 7 | WIP: ID (e.g. camera ID -1 for all IDs)| |"]
2490 MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246,
2491 #[doc = "Override current mission with command to pause mission, pause mission and move to position, continue/resume mission. When param 1 indicates that the mission is paused (MAV_GOTO_DO_HOLD), param 2 defines whether it holds in place or moves to another position."]
2492 #[doc = ""]
2493 #[doc = "# Parameters"]
2494 #[doc = ""]
2495 #[doc = "| Parameter | Description | Values | Units |"]
2496 #[doc = "| --------- | ----------- | ------ | ----- |"]
2497 #[doc = "| 1 (Continue)| MAV_GOTO_DO_HOLD: pause mission and either hold or move to specified position (depending on param2), MAV_GOTO_DO_CONTINUE: resume mission.| [`MavGoto`] | |"]
2498 #[doc = "| 2 (Position)| MAV_GOTO_HOLD_AT_CURRENT_POSITION: hold at current position, MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position.| [`MavGoto`] | |"]
2499 #[doc = "| 3 (Frame) | Coordinate frame of hold point.| [`MavFrame`] | |"]
2500 #[doc = "| 4 (Yaw) | Desired yaw angle.| | deg |"]
2501 #[doc = "| 5 (Latitude/X)| Latitude/X position.| | |"]
2502 #[doc = "| 6 (Longitude/Y)| Longitude/Y position.| | |"]
2503 #[doc = "| 7 (Altitude/Z)| Altitude/Z position.| | |"]
2504 MAV_CMD_OVERRIDE_GOTO = 252,
2505 #[doc = "Mission command to set a Camera Auto Mount Pivoting Oblique Survey (Replaces CAM_TRIGG_DIST for this purpose). The camera is triggered each time this distance is exceeded, then the mount moves to the next position. Params 4~6 set-up the angle limits and number of positions for oblique survey, where mount-enabled vehicles automatically roll the camera between shots to emulate an oblique camera setup (providing an increased HFOV). This command can also be used to set the shutter integration time for the camera."]
2506 #[doc = ""]
2507 #[doc = "# Parameters"]
2508 #[doc = ""]
2509 #[doc = "| Parameter | Description | Values | Units |"]
2510 #[doc = "| --------- | ----------- | ------ | ----- |"]
2511 #[doc = "| 1 (Distance)| Camera trigger distance. 0 to stop triggering.| ≥ 0 | m |"]
2512 #[doc = "| 2 (Shutter)| Camera shutter integration time. 0 to ignore| 0, 1, .. | ms |"]
2513 #[doc = "| 3 (Min Interval)| The minimum interval in which the camera is capable of taking subsequent pictures repeatedly. 0 to ignore.| 0, 1, .. , 10000 | ms |"]
2514 #[doc = "| 4 (Positions)| Total number of roll positions at which the camera will capture photos (images captures spread evenly across the limits defined by param5).| 2, 3, .. | |"]
2515 #[doc = "| 5 (Roll Angle)| Angle limits that the camera can be rolled to left and right of center.| ≥ 0 | deg |"]
2516 #[doc = "| 6 (Pitch Angle)| Fixed pitch angle that the camera will hold in oblique mode if the mount is actuated in the pitch axis.| -180 .. 180 | deg |"]
2517 #[doc = "| 7 | Empty | | |"]
2518 MAV_CMD_OBLIQUE_SURVEY = 260,
2519 #[doc = "Enable the specified standard MAVLink mode. If the specified mode is not supported, the vehicle should ACK with MAV_RESULT_FAILED. See <https://mavlink.io/en/services/standard_modes.html>"]
2520 #[doc = ""]
2521 #[doc = "# Parameters"]
2522 #[doc = ""]
2523 #[doc = "| Parameter | Description | Values |"]
2524 #[doc = "| --------- | ----------- | ------ |"]
2525 #[doc = "| 1 (Standard Mode)| The mode to set.| [`MavStandardMode`] |"]
2526 #[doc = "| 2 | | Reserved (use 0) |"]
2527 #[doc = "| 3 | | Reserved (use 0) |"]
2528 #[doc = "| 4 | | Reserved (use 0) |"]
2529 #[doc = "| 5 | | Reserved (use 0) |"]
2530 #[doc = "| 6 | | Reserved (use 0) |"]
2531 #[doc = "| 7 | | Reserved (use NaN) |"]
2532 MAV_CMD_DO_SET_STANDARD_MODE = 262,
2533 #[doc = "start running a mission"]
2534 #[doc = ""]
2535 #[doc = "# Parameters"]
2536 #[doc = ""]
2537 #[doc = "| Parameter | Description | Values |"]
2538 #[doc = "| --------- | ----------- | ------ |"]
2539 #[doc = "| 1 (First Item)| first_item: the first mission item to run| 0, 1, .. |"]
2540 #[doc = "| 2 (Last Item)| last_item: the last mission item to run (after this item is run, the mission ends)| 0, 1, .. |"]
2541 MAV_CMD_MISSION_START = 300,
2542 #[doc = "Actuator testing command. This is similar to MAV_CMD_DO_MOTOR_TEST but operates on the level of output functions, i.e. it is possible to test Motor1 independent from which output it is configured on. Autopilots must NACK this command with MAV_RESULT_TEMPORARILY_REJECTED while armed."]
2543 #[doc = ""]
2544 #[doc = "# Parameters"]
2545 #[doc = ""]
2546 #[doc = "| Parameter | Description | Values | Units |"]
2547 #[doc = "| --------- | ----------- | ------ | ----- |"]
2548 #[doc = "| 1 (Value) | Output value: 1 means maximum positive output, 0 to center servos or minimum motor thrust (expected to spin), -1 for maximum negative (if not supported by the motors, i.e. motor is not reversible, smaller than 0 maps to NaN). And NaN maps to disarmed (stop the motors).| -1 .. 1 | |"]
2549 #[doc = "| 2 (Timeout)| Timeout after which the test command expires and the output is restored to the previous value. A timeout has to be set for safety reasons. A timeout of 0 means to restore the previous value immediately.| 0 .. 3 | s |"]
2550 #[doc = "| 3 | | Reserved (use 0) | |"]
2551 #[doc = "| 4 | | Reserved (use 0) | |"]
2552 #[doc = "| 5 (Output Function)| Actuator Output function| [`ActuatorOutputFunction`] | |"]
2553 #[doc = "| 6 | | Reserved (use 0) | |"]
2554 #[doc = "| 7 | | Reserved (use 0) | |"]
2555 MAV_CMD_ACTUATOR_TEST = 310,
2556 #[doc = "Actuator configuration command."]
2557 #[doc = ""]
2558 #[doc = "# Parameters"]
2559 #[doc = ""]
2560 #[doc = "| Parameter | Description | Values |"]
2561 #[doc = "| --------- | ----------- | ------ |"]
2562 #[doc = "| 1 (Configuration)| Actuator configuration action| [`ActuatorConfiguration`] |"]
2563 #[doc = "| 2 | | Reserved (use 0) |"]
2564 #[doc = "| 3 | | Reserved (use 0) |"]
2565 #[doc = "| 4 | | Reserved (use 0) |"]
2566 #[doc = "| 5 (Output Function)| Actuator Output function| [`ActuatorOutputFunction`] |"]
2567 #[doc = "| 6 | | Reserved (use 0) |"]
2568 #[doc = "| 7 | | Reserved (use 0) |"]
2569 MAV_CMD_CONFIGURE_ACTUATOR = 311,
2570 #[doc = "Arms / Disarms a component"]
2571 #[doc = ""]
2572 #[doc = "# Parameters"]
2573 #[doc = ""]
2574 #[doc = "| Parameter | Description | Values |"]
2575 #[doc = "| --------- | ----------- | ------ |"]
2576 #[doc = "| 1 (Arm) | 0: disarm, 1: arm| 0, 1 |"]
2577 #[doc = "| 2 (Force) | 0: arm-disarm unless prevented by safety checks (i.e. when landed), 21196: force arming/disarming (e.g. allow arming to override preflight checks and disarming in flight)| 0, 21196 |"]
2578 MAV_CMD_COMPONENT_ARM_DISARM = 400,
2579 #[doc = "Instructs a target system to run pre-arm checks. This allows preflight checks to be run on demand, which may be useful on systems that normally run them at low rate, or which do not trigger checks when the armable state might have changed. This command should return MAV_RESULT_ACCEPTED if it will run the checks. The results of the checks are usually then reported in SYS_STATUS messages (this is system-specific). The command should return MAV_RESULT_TEMPORARILY_REJECTED if the system is already armed."]
2580 MAV_CMD_RUN_PREARM_CHECKS = 401,
2581 #[doc = "Turns illuminators ON/OFF. An illuminator is a light source that is used for lighting up dark areas external to the system: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light)."]
2582 #[doc = ""]
2583 #[doc = "# Parameters"]
2584 #[doc = ""]
2585 #[doc = "| Parameter | Description | Values |"]
2586 #[doc = "| --------- | ----------- | ------ |"]
2587 #[doc = "| 1 (Enable)| 0: Illuminators OFF, 1: Illuminators ON| 0, 1 |"]
2588 MAV_CMD_ILLUMINATOR_ON_OFF = 405,
2589 #[doc = "Configures illuminator settings. An illuminator is a light source that is used for lighting up dark areas external to the system: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light)."]
2590 #[doc = ""]
2591 #[doc = "# Parameters"]
2592 #[doc = ""]
2593 #[doc = "| Parameter | Description | Values | Units |"]
2594 #[doc = "| --------- | ----------- | ------ | ----- |"]
2595 #[doc = "| 1 (Mode) | Mode | [`IlluminatorMode`] | |"]
2596 #[doc = "| 2 (Brightness)| 0%: Off, 100%: Max Brightness| 0 .. 100 | % |"]
2597 #[doc = "| 3 (Strobe Period)| Strobe period in seconds where 0 means strobing is not used| ≥ 0 | s |"]
2598 #[doc = "| 4 (Strobe Duty)| Strobe duty cycle where 100% means it is on constantly and 0 means strobing is not used| 0 .. 100 | % |"]
2599 MAV_CMD_DO_ILLUMINATOR_CONFIGURE = 406,
2600 #[deprecated = " See `MAV_CMD_REQUEST_MESSAGE` (Deprecated since 2022-04)"]
2601 #[doc = "Request the home position from the vehicle. \t The vehicle will ACK the command and then emit the HOME_POSITION message."]
2602 #[doc = ""]
2603 #[doc = "# Parameters"]
2604 #[doc = ""]
2605 #[doc = "| Parameter | Description |"]
2606 #[doc = "| --------- | ----------- |"]
2607 #[doc = "| 1 | Reserved |"]
2608 #[doc = "| 2 | Reserved |"]
2609 #[doc = "| 3 | Reserved |"]
2610 #[doc = "| 4 | Reserved |"]
2611 #[doc = "| 5 | Reserved |"]
2612 #[doc = "| 6 | Reserved |"]
2613 #[doc = "| 7 | Reserved |"]
2614 MAV_CMD_GET_HOME_POSITION = 410,
2615 #[doc = "Inject artificial failure for testing purposes. Note that autopilots should implement an additional protection before accepting this command such as a specific param setting."]
2616 #[doc = ""]
2617 #[doc = "# Parameters"]
2618 #[doc = ""]
2619 #[doc = "| Parameter | Description | Values |"]
2620 #[doc = "| --------- | ----------- | ------ |"]
2621 #[doc = "| 1 (Failure unit)| The unit which is affected by the failure.| [`FailureUnit`] |"]
2622 #[doc = "| 2 (Failure type)| The type how the failure manifests itself.| [`FailureType`] |"]
2623 #[doc = "| 3 (Instance)| Instance affected by failure (0 to signal all).| |"]
2624 MAV_CMD_INJECT_FAILURE = 420,
2625 #[doc = "Starts receiver pairing."]
2626 #[doc = ""]
2627 #[doc = "# Parameters"]
2628 #[doc = ""]
2629 #[doc = "| Parameter | Description | Values |"]
2630 #[doc = "| --------- | ----------- | ------ |"]
2631 #[doc = "| 1 (RC Type)| RC type. | [`RcType`] |"]
2632 #[doc = "| 2 (RC Sub Type)| RC sub type.| [`RcSubType`] |"]
2633 MAV_CMD_START_RX_PAIR = 500,
2634 #[deprecated = " See `MAV_CMD_REQUEST_MESSAGE` (Deprecated since 2022-04)"]
2635 #[doc = "Request the interval between messages for a particular MAVLink message ID. The receiver should ACK the command and then emit its response in a MESSAGE_INTERVAL message."]
2636 #[doc = ""]
2637 #[doc = "# Parameters"]
2638 #[doc = ""]
2639 #[doc = "| Parameter | Description | Values |"]
2640 #[doc = "| --------- | ----------- | ------ |"]
2641 #[doc = "| 1 (Message ID)| The MAVLink message ID| 0, 1, .. , 16777215 |"]
2642 MAV_CMD_GET_MESSAGE_INTERVAL = 510,
2643 #[doc = "Set the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM."]
2644 #[doc = ""]
2645 #[doc = "# Parameters"]
2646 #[doc = ""]
2647 #[doc = "| Parameter | Description | Values | Units |"]
2648 #[doc = "| --------- | ----------- | ------ | ----- |"]
2649 #[doc = "| 1 (Message ID)| The MAVLink message ID| 0, 1, .. , 16777215 | |"]
2650 #[doc = "| 2 (Interval)| The interval between two messages. -1: disable. 0: request default rate (which may be zero).| -1, 0, .. | us |"]
2651 #[doc = "| 3 (Req Param 3)| Use for index ID, if required. Otherwise, the use of this parameter (if any) must be defined in the requested message. By default assumed not used (0). When used as an index ID, 0 means \"all instances\", \"1\" means the first instance in the sequence (the emitted message will have an id of 0 if message ids are 0-indexed, or 1 if index numbers start from one).| | |"]
2652 #[doc = "| 4 (Req Param 4)| The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).| | |"]
2653 #[doc = "| 5 (Req Param 5)| The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0/NaN).| | |"]
2654 #[doc = "| 6 (Req Param 6)| The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0/NaN).| | |"]
2655 #[doc = "| 7 (Response Target)| Target address of message stream (if message has target address fields). 0: Flight-stack default (recommended), 1: address of requestor, 2: broadcast.| 0, 1, 2 | |"]
2656 MAV_CMD_SET_MESSAGE_INTERVAL = 511,
2657 #[doc = "Request the target system(s) emit a single instance of a specified message (i.e. a \"one-shot\" version of MAV_CMD_SET_MESSAGE_INTERVAL)."]
2658 #[doc = ""]
2659 #[doc = "# Parameters"]
2660 #[doc = ""]
2661 #[doc = "| Parameter | Description | Values |"]
2662 #[doc = "| --------- | ----------- | ------ |"]
2663 #[doc = "| 1 (Message ID)| The MAVLink message ID of the requested message.| 0, 1, .. , 16777215 |"]
2664 #[doc = "| 2 (Req Param 1)| Use for index ID, if required. Otherwise, the use of this parameter (if any) must be defined in the requested message. By default assumed not used (0).| |"]
2665 #[doc = "| 3 (Req Param 2)| The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).| |"]
2666 #[doc = "| 4 (Req Param 3)| The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).| |"]
2667 #[doc = "| 5 (Req Param 4)| The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).| |"]
2668 #[doc = "| 6 (Req Param 5)| The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).| |"]
2669 #[doc = "| 7 (Response Target)| Target address for requested message (if message has target address fields). 0: Flight-stack default, 1: address of requestor, 2: broadcast.| 0, 1, 2 |"]
2670 MAV_CMD_REQUEST_MESSAGE = 512,
2671 #[deprecated = " See `MAV_CMD_REQUEST_MESSAGE` (Deprecated since 2019-08)"]
2672 #[doc = "Request MAVLink protocol version compatibility. All receivers should ACK the command and then emit their capabilities in an PROTOCOL_VERSION message"]
2673 #[doc = ""]
2674 #[doc = "# Parameters"]
2675 #[doc = ""]
2676 #[doc = "| Parameter | Description | Values |"]
2677 #[doc = "| --------- | ----------- | ------ |"]
2678 #[doc = "| 1 (Protocol)| 1: Request supported protocol versions by all nodes on the network| 0, 1 |"]
2679 #[doc = "| 2 | Reserved (all remaining params)| |"]
2680 MAV_CMD_REQUEST_PROTOCOL_VERSION = 519,
2681 #[deprecated = " See `MAV_CMD_REQUEST_MESSAGE` (Deprecated since 2019-08)"]
2682 #[doc = "Request autopilot capabilities. The receiver should ACK the command and then emit its capabilities in an AUTOPILOT_VERSION message"]
2683 #[doc = ""]
2684 #[doc = "# Parameters"]
2685 #[doc = ""]
2686 #[doc = "| Parameter | Description | Values |"]
2687 #[doc = "| --------- | ----------- | ------ |"]
2688 #[doc = "| 1 (Version)| 1: Request autopilot version| 0, 1 |"]
2689 #[doc = "| 2 | Reserved (all remaining params)| |"]
2690 MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES = 520,
2691 #[deprecated = " See `MAV_CMD_REQUEST_MESSAGE` (Deprecated since 2019-08)"]
2692 #[doc = "Request camera information (CAMERA_INFORMATION)."]
2693 #[doc = ""]
2694 #[doc = "# Parameters"]
2695 #[doc = ""]
2696 #[doc = "| Parameter | Description | Values |"]
2697 #[doc = "| --------- | ----------- | ------ |"]
2698 #[doc = "| 1 (Capabilities)| 0: No action 1: Request camera capabilities| 0, 1 |"]
2699 #[doc = "| 2 | Reserved (all remaining params)| |"]
2700 MAV_CMD_REQUEST_CAMERA_INFORMATION = 521,
2701 #[deprecated = " See `MAV_CMD_REQUEST_MESSAGE` (Deprecated since 2019-08)"]
2702 #[doc = "Request camera settings (CAMERA_SETTINGS)."]
2703 #[doc = ""]
2704 #[doc = "# Parameters"]
2705 #[doc = ""]
2706 #[doc = "| Parameter | Description | Values |"]
2707 #[doc = "| --------- | ----------- | ------ |"]
2708 #[doc = "| 1 (Settings)| 0: No Action 1: Request camera settings| 0, 1 |"]
2709 #[doc = "| 2 | Reserved (all remaining params)| |"]
2710 MAV_CMD_REQUEST_CAMERA_SETTINGS = 522,
2711 #[deprecated = " See `MAV_CMD_REQUEST_MESSAGE` (Deprecated since 2019-08)"]
2712 #[doc = "Request storage information (STORAGE_INFORMATION). Use the command's target_component to target a specific component's storage."]
2713 #[doc = ""]
2714 #[doc = "# Parameters"]
2715 #[doc = ""]
2716 #[doc = "| Parameter | Description | Values |"]
2717 #[doc = "| --------- | ----------- | ------ |"]
2718 #[doc = "| 1 (Storage ID)| Storage ID (0 for all, 1 for first, 2 for second, etc.)| 0, 1, .. |"]
2719 #[doc = "| 2 (Information)| 0: No Action 1: Request storage information| 0, 1 |"]
2720 #[doc = "| 3 | Reserved (all remaining params)| |"]
2721 MAV_CMD_REQUEST_STORAGE_INFORMATION = 525,
2722 #[doc = "Format a storage medium. Once format is complete, a STORAGE_INFORMATION message is sent. Use the command's target_component to target a specific component's storage."]
2723 #[doc = ""]
2724 #[doc = "# Parameters"]
2725 #[doc = ""]
2726 #[doc = "| Parameter | Description | Values |"]
2727 #[doc = "| --------- | ----------- | ------ |"]
2728 #[doc = "| 1 (Storage ID)| Storage ID (1 for first, 2 for second, etc.)| 0, 1, .. |"]
2729 #[doc = "| 2 (Format)| Format storage (and reset image log). 0: No action 1: Format storage| 0, 1 |"]
2730 #[doc = "| 3 (Reset Image Log)| Reset Image Log (without formatting storage medium). This will reset CAMERA_CAPTURE_STATUS.image_count and CAMERA_IMAGE_CAPTURED.image_index. 0: No action 1: Reset Image Log| 0, 1 |"]
2731 #[doc = "| 4 | Reserved (all remaining params)| |"]
2732 MAV_CMD_STORAGE_FORMAT = 526,
2733 #[deprecated = " See `MAV_CMD_REQUEST_MESSAGE` (Deprecated since 2019-08)"]
2734 #[doc = "Request camera capture status (CAMERA_CAPTURE_STATUS)"]
2735 #[doc = ""]
2736 #[doc = "# Parameters"]
2737 #[doc = ""]
2738 #[doc = "| Parameter | Description | Values |"]
2739 #[doc = "| --------- | ----------- | ------ |"]
2740 #[doc = "| 1 (Capture Status)| 0: No Action 1: Request camera capture status| 0, 1 |"]
2741 #[doc = "| 2 | Reserved (all remaining params)| |"]
2742 MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS = 527,
2743 #[deprecated = " See `MAV_CMD_REQUEST_MESSAGE` (Deprecated since 2019-08)"]
2744 #[doc = "Request flight information (FLIGHT_INFORMATION)"]
2745 #[doc = ""]
2746 #[doc = "# Parameters"]
2747 #[doc = ""]
2748 #[doc = "| Parameter | Description | Values |"]
2749 #[doc = "| --------- | ----------- | ------ |"]
2750 #[doc = "| 1 (Flight Information)| 1: Request flight information| 0, 1 |"]
2751 #[doc = "| 2 | Reserved (all remaining params)| |"]
2752 MAV_CMD_REQUEST_FLIGHT_INFORMATION = 528,
2753 #[doc = "Reset all camera settings to Factory Default"]
2754 #[doc = ""]
2755 #[doc = "# Parameters"]
2756 #[doc = ""]
2757 #[doc = "| Parameter | Description | Values |"]
2758 #[doc = "| --------- | ----------- | ------ |"]
2759 #[doc = "| 1 (Reset) | 0: No Action 1: Reset all settings| 0, 1 |"]
2760 #[doc = "| 2 (Target Camera ID)| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| 0, 1, .. , 255 |"]
2761 MAV_CMD_RESET_CAMERA_SETTINGS = 529,
2762 #[doc = "Set camera running mode. Use NaN for reserved values. GCS will send a MAV_CMD_REQUEST_VIDEO_STREAM_STATUS command after a mode change if the camera supports video streaming."]
2763 #[doc = ""]
2764 #[doc = "# Parameters"]
2765 #[doc = ""]
2766 #[doc = "| Parameter | Description | Values |"]
2767 #[doc = "| --------- | ----------- | ------ |"]
2768 #[doc = "| 1 (id) | Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| 0, 1, .. , 255 |"]
2769 #[doc = "| 2 (Camera Mode)| Camera mode | [`CameraMode`] |"]
2770 #[doc = "| 3 | | Reserved (use NaN) |"]
2771 #[doc = "| 4 | | Reserved (use NaN) |"]
2772 #[doc = "| 5 | | |"]
2773 #[doc = "| 6 | | |"]
2774 #[doc = "| 7 | | Reserved (use NaN) |"]
2775 MAV_CMD_SET_CAMERA_MODE = 530,
2776 #[doc = "Set camera zoom. Camera must respond with a CAMERA_SETTINGS message (on success)."]
2777 #[doc = ""]
2778 #[doc = "# Parameters"]
2779 #[doc = ""]
2780 #[doc = "| Parameter | Description | Values |"]
2781 #[doc = "| --------- | ----------- | ------ |"]
2782 #[doc = "| 1 (Zoom Type)| Zoom type | [`CameraZoomType`] |"]
2783 #[doc = "| 2 (Zoom Value)| Zoom value. The range of valid values depend on the zoom type.| |"]
2784 #[doc = "| 3 (Target Camera ID)| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| 0, 1, .. , 255 |"]
2785 #[doc = "| 4 | | Reserved (use NaN) |"]
2786 MAV_CMD_SET_CAMERA_ZOOM = 531,
2787 #[doc = "Set camera focus. Camera must respond with a CAMERA_SETTINGS message (on success)."]
2788 #[doc = ""]
2789 #[doc = "# Parameters"]
2790 #[doc = ""]
2791 #[doc = "| Parameter | Description | Values |"]
2792 #[doc = "| --------- | ----------- | ------ |"]
2793 #[doc = "| 1 (Focus Type)| Focus type | [`SetFocusType`] |"]
2794 #[doc = "| 2 (Focus Value)| Focus value | |"]
2795 #[doc = "| 3 (Target Camera ID)| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| 0, 1, .. , 255 |"]
2796 #[doc = "| 4 | | Reserved (use NaN) |"]
2797 MAV_CMD_SET_CAMERA_FOCUS = 532,
2798 #[doc = "Set that a particular storage is the preferred location for saving photos, videos, and/or other media (e.g. to set that an SD card is used for storing videos). There can only be one preferred save location for each particular media type: setting a media usage flag will clear/reset that same flag if set on any other storage. If no flag is set the system should use its default storage. A target system can choose to always use default storage, in which case it should ACK the command with MAV_RESULT_UNSUPPORTED. A target system can choose to not allow a particular storage to be set as preferred storage, in which case it should ACK the command with MAV_RESULT_DENIED."]
2799 #[doc = ""]
2800 #[doc = "# Parameters"]
2801 #[doc = ""]
2802 #[doc = "| Parameter | Description | Values |"]
2803 #[doc = "| --------- | ----------- | ------ |"]
2804 #[doc = "| 1 (Storage ID)| Storage ID (1 for first, 2 for second, etc.)| 0, 1, .. |"]
2805 #[doc = "| 2 (Usage) | Usage flags | [`StorageUsageFlag`] |"]
2806 MAV_CMD_SET_STORAGE_USAGE = 533,
2807 #[doc = "Set camera source. Changes the camera's active sources on cameras with multiple image sensors."]
2808 #[doc = ""]
2809 #[doc = "# Parameters"]
2810 #[doc = ""]
2811 #[doc = "| Parameter | Description | Values |"]
2812 #[doc = "| --------- | ----------- | ------ |"]
2813 #[doc = "| 1 (device id)| Component Id of camera to address or 1-6 for non-MAVLink cameras, 0 for all cameras.| |"]
2814 #[doc = "| 2 (primary source)| Primary Source| [`CameraSource`] |"]
2815 #[doc = "| 3 (secondary source)| Secondary Source. If non-zero the second source will be displayed as picture-in-picture.| [`CameraSource`] |"]
2816 MAV_CMD_SET_CAMERA_SOURCE = 534,
2817 #[doc = "Tagged jump target. Can be jumped to with MAV_CMD_DO_JUMP_TAG."]
2818 #[doc = ""]
2819 #[doc = "# Parameters"]
2820 #[doc = ""]
2821 #[doc = "| Parameter | Description | Values |"]
2822 #[doc = "| --------- | ----------- | ------ |"]
2823 #[doc = "| 1 (Tag) | Tag. | 0, 1, .. |"]
2824 MAV_CMD_JUMP_TAG = 600,
2825 #[doc = "Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number."]
2826 #[doc = ""]
2827 #[doc = "# Parameters"]
2828 #[doc = ""]
2829 #[doc = "| Parameter | Description | Values |"]
2830 #[doc = "| --------- | ----------- | ------ |"]
2831 #[doc = "| 1 (Tag) | Target tag to jump to.| 0, 1, .. |"]
2832 #[doc = "| 2 (Repeat)| Repeat count.| 0, 1, .. |"]
2833 MAV_CMD_DO_JUMP_TAG = 601,
2834 #[doc = "Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate."]
2835 #[doc = ""]
2836 #[doc = "# Parameters"]
2837 #[doc = ""]
2838 #[doc = "| Parameter | Description | Values | Units |"]
2839 #[doc = "| --------- | ----------- | ------ | ----- |"]
2840 #[doc = "| 1 (Pitch angle)| Pitch angle (positive to pitch up, relative to vehicle for FOLLOW mode, relative to world horizon for LOCK mode).| -180 .. 180 | deg |"]
2841 #[doc = "| 2 (Yaw angle)| Yaw angle (positive to yaw to the right, relative to vehicle for FOLLOW mode, absolute to North for LOCK mode).| -180 .. 180 | deg |"]
2842 #[doc = "| 3 (Pitch rate)| Pitch rate (positive to pitch up).| | deg/s |"]
2843 #[doc = "| 4 (Yaw rate)| Yaw rate (positive to yaw to the right).| | deg/s |"]
2844 #[doc = "| 5 (Gimbal manager flags)| Gimbal manager flags to use.| [`GimbalManagerFlags`] | |"]
2845 #[doc = "| 6 | | | |"]
2846 #[doc = "| 7 (Gimbal device ID)| Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).| | |"]
2847 MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1000,
2848 #[doc = "Gimbal configuration to set which sysid/compid is in primary and secondary control."]
2849 #[doc = ""]
2850 #[doc = "# Parameters"]
2851 #[doc = ""]
2852 #[doc = "| Parameter | Description |"]
2853 #[doc = "| --------- | ----------- |"]
2854 #[doc = "| 1 (sysid primary control)| Sysid for primary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).|"]
2855 #[doc = "| 2 (compid primary control)| Compid for primary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).|"]
2856 #[doc = "| 3 (sysid secondary control)| Sysid for secondary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).|"]
2857 #[doc = "| 4 (compid secondary control)| Compid for secondary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).|"]
2858 #[doc = "| 5 | |"]
2859 #[doc = "| 6 | |"]
2860 #[doc = "| 7 (Gimbal device ID)| Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).|"]
2861 MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1001,
2862 #[doc = "Start image capture sequence. CAMERA_IMAGE_CAPTURED must be emitted after each capture. Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID. It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID). It is also needed to specify the target camera in missions. When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command's target_component as the param1 value (and setting param1 in the command to zero). If the param1 is 0 the autopilot should do both. When sent in a command the target MAVLink address is set using target_component. If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist). If addressed to a MAVLink camera, param 1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED. If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels."]
2863 #[doc = ""]
2864 #[doc = "# Parameters"]
2865 #[doc = ""]
2866 #[doc = "| Parameter | Description | Values | Units |"]
2867 #[doc = "| --------- | ----------- | ------ | ----- |"]
2868 #[doc = "| 1 (Target Camera ID)| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| 0, 1, .. , 255 | |"]
2869 #[doc = "| 2 (Interval)| Desired elapsed time between two consecutive pictures (in seconds). Minimum values depend on hardware (typically greater than 2 seconds).| ≥ 0 | s |"]
2870 #[doc = "| 3 (Total Images)| Total number of images to capture. 0 to capture forever/until MAV_CMD_IMAGE_STOP_CAPTURE.| 0, 1, .. | |"]
2871 #[doc = "| 4 (Sequence Number)| Capture sequence number starting from 1. This is only valid for single-capture (param3 == 1), otherwise set to 0. Increment the capture ID for each capture command to prevent double captures when a command is re-transmitted.| 1, 2, .. | |"]
2872 #[doc = "| 5 | | | |"]
2873 #[doc = "| 6 | | | |"]
2874 #[doc = "| 7 | | Reserved (use NaN) | |"]
2875 MAV_CMD_IMAGE_START_CAPTURE = 2000,
2876 #[doc = "Stop image capture sequence. Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID. It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID). It is also needed to specify the target camera in missions. When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command's target_component as the param1 value (and setting param1 in the command to zero). If the param1 is 0 the autopilot should do both. When sent in a command the target MAVLink address is set using target_component. If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist). If addressed to a MAVLink camera, param1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED. If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels."]
2877 #[doc = ""]
2878 #[doc = "# Parameters"]
2879 #[doc = ""]
2880 #[doc = "| Parameter | Description | Values |"]
2881 #[doc = "| --------- | ----------- | ------ |"]
2882 #[doc = "| 1 (Target Camera ID)| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| 0, 1, .. , 255 |"]
2883 #[doc = "| 2 | | Reserved (use NaN) |"]
2884 #[doc = "| 3 | | Reserved (use NaN) |"]
2885 #[doc = "| 4 | | Reserved (use NaN) |"]
2886 #[doc = "| 5 | | |"]
2887 #[doc = "| 6 | | |"]
2888 #[doc = "| 7 | | Reserved (use NaN) |"]
2889 MAV_CMD_IMAGE_STOP_CAPTURE = 2001,
2890 #[deprecated = " See `MAV_CMD_REQUEST_MESSAGE` (Deprecated since 2019-08)"]
2891 #[doc = "Re-request a CAMERA_IMAGE_CAPTURED message."]
2892 #[doc = ""]
2893 #[doc = "# Parameters"]
2894 #[doc = ""]
2895 #[doc = "| Parameter | Description | Values |"]
2896 #[doc = "| --------- | ----------- | ------ |"]
2897 #[doc = "| 1 (Number)| Sequence number for missing CAMERA_IMAGE_CAPTURED message| 0, 1, .. |"]
2898 #[doc = "| 2 | | Reserved (use NaN) |"]
2899 #[doc = "| 3 | | Reserved (use NaN) |"]
2900 #[doc = "| 4 | | Reserved (use NaN) |"]
2901 #[doc = "| 5 | | |"]
2902 #[doc = "| 6 | | |"]
2903 #[doc = "| 7 | | Reserved (use NaN) |"]
2904 MAV_CMD_REQUEST_CAMERA_IMAGE_CAPTURE = 2002,
2905 #[doc = "Enable or disable on-board camera triggering system."]
2906 #[doc = ""]
2907 #[doc = "# Parameters"]
2908 #[doc = ""]
2909 #[doc = "| Parameter | Description | Values |"]
2910 #[doc = "| --------- | ----------- | ------ |"]
2911 #[doc = "| 1 (Enable)| Trigger enable/disable (0 for disable, 1 for start), -1 to ignore| -1, 0, 1 |"]
2912 #[doc = "| 2 (Reset) | 1 to reset the trigger sequence, -1 or 0 to ignore| -1, 0, 1 |"]
2913 #[doc = "| 3 (Pause) | 1 to pause triggering, but without switching the camera off or retracting it. -1 to ignore| -1, 1 |"]
2914 #[doc = "| 4 (Target Camera ID)| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| 0, 1, .. , 255 |"]
2915 MAV_CMD_DO_TRIGGER_CONTROL = 2003,
2916 #[doc = "If the camera supports point visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_POINT is set), this command allows to initiate the tracking."]
2917 #[doc = ""]
2918 #[doc = "# Parameters"]
2919 #[doc = ""]
2920 #[doc = "| Parameter | Description | Values |"]
2921 #[doc = "| --------- | ----------- | ------ |"]
2922 #[doc = "| 1 (Point x)| Point to track x value (normalized 0..1, 0 is left, 1 is right).| 0 .. 1 |"]
2923 #[doc = "| 2 (Point y)| Point to track y value (normalized 0..1, 0 is top, 1 is bottom).| 0 .. 1 |"]
2924 #[doc = "| 3 (Radius)| Point radius (normalized 0..1, 0 is one pixel, 1 is full image width).| 0 .. 1 |"]
2925 #[doc = "| 4 (Target Camera ID)| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| 0, 1, .. , 255 |"]
2926 MAV_CMD_CAMERA_TRACK_POINT = 2004,
2927 #[doc = "If the camera supports rectangle visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE is set), this command allows to initiate the tracking."]
2928 #[doc = ""]
2929 #[doc = "# Parameters"]
2930 #[doc = ""]
2931 #[doc = "| Parameter | Description | Values |"]
2932 #[doc = "| --------- | ----------- | ------ |"]
2933 #[doc = "| 1 (Top left corner x)| Top left corner of rectangle x value (normalized 0..1, 0 is left, 1 is right).| 0 .. 1 |"]
2934 #[doc = "| 2 (Top left corner y)| Top left corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom).| 0 .. 1 |"]
2935 #[doc = "| 3 (Bottom right corner x)| Bottom right corner of rectangle x value (normalized 0..1, 0 is left, 1 is right).| 0 .. 1 |"]
2936 #[doc = "| 4 (Bottom right corner y)| Bottom right corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom).| 0 .. 1 |"]
2937 #[doc = "| 5 (Target Camera ID)| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| 0, 1, .. , 255 |"]
2938 MAV_CMD_CAMERA_TRACK_RECTANGLE = 2005,
2939 #[doc = "Stops ongoing tracking."]
2940 #[doc = ""]
2941 #[doc = "# Parameters"]
2942 #[doc = ""]
2943 #[doc = "| Parameter | Description | Values |"]
2944 #[doc = "| --------- | ----------- | ------ |"]
2945 #[doc = "| 1 (Target Camera ID)| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| 0, 1, .. , 255 |"]
2946 MAV_CMD_CAMERA_STOP_TRACKING = 2010,
2947 #[doc = "Starts video capture (recording)."]
2948 #[doc = ""]
2949 #[doc = "# Parameters"]
2950 #[doc = ""]
2951 #[doc = "| Parameter | Description | Values | Units |"]
2952 #[doc = "| --------- | ----------- | ------ | ----- |"]
2953 #[doc = "| 1 (Stream ID)| Video Stream ID (0 for all streams)| 0, 1, .. | |"]
2954 #[doc = "| 2 (Status Frequency)| Frequency CAMERA_CAPTURE_STATUS messages should be sent while recording (0 for no messages, otherwise frequency)| ≥ 0 | Hz |"]
2955 #[doc = "| 3 (Target Camera ID)| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| 0, 1, .. , 255 | |"]
2956 #[doc = "| 4 | | Reserved (use NaN) | |"]
2957 #[doc = "| 5 | | | |"]
2958 #[doc = "| 6 | | | |"]
2959 #[doc = "| 7 | | Reserved (use NaN) | |"]
2960 MAV_CMD_VIDEO_START_CAPTURE = 2500,
2961 #[doc = "Stop the current video capture (recording)."]
2962 #[doc = ""]
2963 #[doc = "# Parameters"]
2964 #[doc = ""]
2965 #[doc = "| Parameter | Description | Values |"]
2966 #[doc = "| --------- | ----------- | ------ |"]
2967 #[doc = "| 1 (Stream ID)| Video Stream ID (0 for all streams)| 0, 1, .. |"]
2968 #[doc = "| 2 (Target Camera ID)| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| 0, 1, .. , 255 |"]
2969 #[doc = "| 3 | | Reserved (use NaN) |"]
2970 #[doc = "| 4 | | Reserved (use NaN) |"]
2971 #[doc = "| 5 | | |"]
2972 #[doc = "| 6 | | |"]
2973 #[doc = "| 7 | | Reserved (use NaN) |"]
2974 MAV_CMD_VIDEO_STOP_CAPTURE = 2501,
2975 #[doc = "Start video streaming"]
2976 #[doc = ""]
2977 #[doc = "# Parameters"]
2978 #[doc = ""]
2979 #[doc = "| Parameter | Description | Values |"]
2980 #[doc = "| --------- | ----------- | ------ |"]
2981 #[doc = "| 1 (Stream ID)| Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.)| 0, 1, .. |"]
2982 #[doc = "| 2 (Target Camera ID)| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| 0, 1, .. , 255 |"]
2983 MAV_CMD_VIDEO_START_STREAMING = 2502,
2984 #[doc = "Stop the given video stream"]
2985 #[doc = ""]
2986 #[doc = "# Parameters"]
2987 #[doc = ""]
2988 #[doc = "| Parameter | Description | Values |"]
2989 #[doc = "| --------- | ----------- | ------ |"]
2990 #[doc = "| 1 (Stream ID)| Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.)| 0, 1, .. |"]
2991 #[doc = "| 2 (Target Camera ID)| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| 0, 1, .. , 255 |"]
2992 MAV_CMD_VIDEO_STOP_STREAMING = 2503,
2993 #[deprecated = " See `MAV_CMD_REQUEST_MESSAGE` (Deprecated since 2019-08)"]
2994 #[doc = "Request video stream information (VIDEO_STREAM_INFORMATION)"]
2995 #[doc = ""]
2996 #[doc = "# Parameters"]
2997 #[doc = ""]
2998 #[doc = "| Parameter | Description | Values |"]
2999 #[doc = "| --------- | ----------- | ------ |"]
3000 #[doc = "| 1 (Stream ID)| Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.)| 0, 1, .. |"]
3001 MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION = 2504,
3002 #[deprecated = " See `MAV_CMD_REQUEST_MESSAGE` (Deprecated since 2019-08)"]
3003 #[doc = "Request video stream status (VIDEO_STREAM_STATUS)"]
3004 #[doc = ""]
3005 #[doc = "# Parameters"]
3006 #[doc = ""]
3007 #[doc = "| Parameter | Description | Values |"]
3008 #[doc = "| --------- | ----------- | ------ |"]
3009 #[doc = "| 1 (Stream ID)| Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.)| 0, 1, .. |"]
3010 MAV_CMD_REQUEST_VIDEO_STREAM_STATUS = 2505,
3011 #[doc = "Request to start streaming logging data over MAVLink (see also LOGGING_DATA message)"]
3012 #[doc = ""]
3013 #[doc = "# Parameters"]
3014 #[doc = ""]
3015 #[doc = "| Parameter | Description | Values |"]
3016 #[doc = "| --------- | ----------- | ------ |"]
3017 #[doc = "| 1 (Format)| Format: 0: ULog| 0, 1, .. |"]
3018 #[doc = "| 2 | Reserved (set to 0)| |"]
3019 #[doc = "| 3 | Reserved (set to 0)| |"]
3020 #[doc = "| 4 | Reserved (set to 0)| |"]
3021 #[doc = "| 5 | Reserved (set to 0)| |"]
3022 #[doc = "| 6 | Reserved (set to 0)| |"]
3023 #[doc = "| 7 | Reserved (set to 0)| |"]
3024 MAV_CMD_LOGGING_START = 2510,
3025 #[doc = "Request to stop streaming log data over MAVLink"]
3026 #[doc = ""]
3027 #[doc = "# Parameters"]
3028 #[doc = ""]
3029 #[doc = "| Parameter | Description |"]
3030 #[doc = "| --------- | ----------- |"]
3031 #[doc = "| 1 | Reserved (set to 0)|"]
3032 #[doc = "| 2 | Reserved (set to 0)|"]
3033 #[doc = "| 3 | Reserved (set to 0)|"]
3034 #[doc = "| 4 | Reserved (set to 0)|"]
3035 #[doc = "| 5 | Reserved (set to 0)|"]
3036 #[doc = "| 6 | Reserved (set to 0)|"]
3037 #[doc = "| 7 | Reserved (set to 0)|"]
3038 MAV_CMD_LOGGING_STOP = 2511,
3039 #[doc = ""]
3040 #[doc = "# Parameters"]
3041 #[doc = ""]
3042 #[doc = "| Parameter | Description | Values |"]
3043 #[doc = "| --------- | ----------- | ------ |"]
3044 #[doc = "| 1 (Landing Gear ID)| Landing gear ID (default: 0, -1 for all)| -1, 0, .. |"]
3045 #[doc = "| 2 (Landing Gear Position)| Landing gear position (Down: 0, Up: 1, NaN for no change)| |"]
3046 #[doc = "| 3 | | Reserved (use NaN) |"]
3047 #[doc = "| 4 | | Reserved (use NaN) |"]
3048 #[doc = "| 5 | | |"]
3049 #[doc = "| 6 | | |"]
3050 #[doc = "| 7 | | Reserved (use NaN) |"]
3051 MAV_CMD_AIRFRAME_CONFIGURATION = 2520,
3052 #[doc = "Request to start/stop transmitting over the high latency telemetry"]
3053 #[doc = ""]
3054 #[doc = "# Parameters"]
3055 #[doc = ""]
3056 #[doc = "| Parameter | Description | Values |"]
3057 #[doc = "| --------- | ----------- | ------ |"]
3058 #[doc = "| 1 (Enable)| Control transmission over high latency telemetry (0: stop, 1: start)| 0, 1 |"]
3059 #[doc = "| 2 | Empty | |"]
3060 #[doc = "| 3 | Empty | |"]
3061 #[doc = "| 4 | Empty | |"]
3062 #[doc = "| 5 | Empty | |"]
3063 #[doc = "| 6 | Empty | |"]
3064 #[doc = "| 7 | Empty | |"]
3065 MAV_CMD_CONTROL_HIGH_LATENCY = 2600,
3066 #[doc = "Create a panorama at the current position"]
3067 #[doc = ""]
3068 #[doc = "# Parameters"]
3069 #[doc = ""]
3070 #[doc = "| Parameter | Description | Units |"]
3071 #[doc = "| --------- | ----------- | ----- |"]
3072 #[doc = "| 1 (Horizontal Angle)| Viewing angle horizontal of the panorama (+- 0.5 the total angle)| deg |"]
3073 #[doc = "| 2 (Vertical Angle)| Viewing angle vertical of panorama.| deg |"]
3074 #[doc = "| 3 (Horizontal Speed)| Speed of the horizontal rotation.| deg/s |"]
3075 #[doc = "| 4 (Vertical Speed)| Speed of the vertical rotation.| deg/s |"]
3076 MAV_CMD_PANORAMA_CREATE = 2800,
3077 #[doc = "Request VTOL transition"]
3078 #[doc = ""]
3079 #[doc = "# Parameters"]
3080 #[doc = ""]
3081 #[doc = "| Parameter | Description | Values |"]
3082 #[doc = "| --------- | ----------- | ------ |"]
3083 #[doc = "| 1 (State) | The target VTOL state. For normal transitions, only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.| [`MavVtolState`] |"]
3084 #[doc = "| 2 (Immediate)| Force immediate transition to the specified MAV_VTOL_STATE. 1: Force immediate, 0: normal transition. Can be used, for example, to trigger an emergency \"Quadchute\". Caution: Can be dangerous/damage vehicle, depending on autopilot implementation of this command.| |"]
3085 MAV_CMD_DO_VTOL_TRANSITION = 3000,
3086 #[doc = "Request authorization to arm the vehicle to a external entity, the arm authorizer is responsible to request all data that is needs from the vehicle before authorize or deny the request. \t\tIf approved the COMMAND_ACK message progress field should be set with period of time that this authorization is valid in seconds. \t\tIf the authorization is denied COMMAND_ACK.result_param2 should be set with one of the reasons in ARM_AUTH_DENIED_REASON."]
3087 #[doc = ""]
3088 #[doc = "# Parameters"]
3089 #[doc = ""]
3090 #[doc = "| Parameter | Description | Values |"]
3091 #[doc = "| --------- | ----------- | ------ |"]
3092 #[doc = "| 1 (System ID)| Vehicle system id, this way ground station can request arm authorization on behalf of any vehicle| 0, 1, .. , 255 |"]
3093 MAV_CMD_ARM_AUTHORIZATION_REQUEST = 3001,
3094 #[doc = "This command sets the submode to standard guided when vehicle is in guided mode. The vehicle holds position and altitude and the user can input the desired velocities along all three axes."]
3095 MAV_CMD_SET_GUIDED_SUBMODE_STANDARD = 4000,
3096 #[doc = "This command sets submode circle when vehicle is in guided mode. Vehicle flies along a circle facing the center of the circle. The user can input the velocity along the circle and change the radius. If no input is given the vehicle will hold position."]
3097 #[doc = ""]
3098 #[doc = "# Parameters"]
3099 #[doc = ""]
3100 #[doc = "| Parameter | Description | Units |"]
3101 #[doc = "| --------- | ----------- | ----- |"]
3102 #[doc = "| 1 (Radius)| Radius of desired circle in CIRCLE_MODE| m |"]
3103 #[doc = "| 2 | User defined| |"]
3104 #[doc = "| 3 | User defined| |"]
3105 #[doc = "| 4 | User defined| |"]
3106 #[doc = "| 5 (Latitude)| Target latitude of center of circle in CIRCLE_MODE| degE7 |"]
3107 #[doc = "| 6 (Longitude)| Target longitude of center of circle in CIRCLE_MODE| degE7 |"]
3108 MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE = 4001,
3109 #[doc = "Delay mission state machine until gate has been reached."]
3110 #[doc = ""]
3111 #[doc = "# Parameters"]
3112 #[doc = ""]
3113 #[doc = "| Parameter | Description | Values | Units |"]
3114 #[doc = "| --------- | ----------- | ------ | ----- |"]
3115 #[doc = "| 1 (Geometry)| Geometry: 0: orthogonal to path between previous and next waypoint.| 0, 1, .. | |"]
3116 #[doc = "| 2 (UseAltitude)| Altitude: 0: ignore altitude| 0, 1 | |"]
3117 #[doc = "| 3 | Empty | | |"]
3118 #[doc = "| 4 | Empty | | |"]
3119 #[doc = "| 5 (Latitude)| Latitude | | |"]
3120 #[doc = "| 6 (Longitude)| Longitude | | |"]
3121 #[doc = "| 7 (Altitude)| Altitude | | m |"]
3122 MAV_CMD_CONDITION_GATE = 4501,
3123 #[doc = "Fence return point (there can only be one such point in a geofence definition). If rally points are supported they should be used instead."]
3124 #[doc = ""]
3125 #[doc = "# Parameters"]
3126 #[doc = ""]
3127 #[doc = "| Parameter | Description | Units |"]
3128 #[doc = "| --------- | ----------- | ----- |"]
3129 #[doc = "| 1 | Reserved | |"]
3130 #[doc = "| 2 | Reserved | |"]
3131 #[doc = "| 3 | Reserved | |"]
3132 #[doc = "| 4 | Reserved | |"]
3133 #[doc = "| 5 (Latitude)| Latitude | |"]
3134 #[doc = "| 6 (Longitude)| Longitude | |"]
3135 #[doc = "| 7 (Altitude)| Altitude | m |"]
3136 MAV_CMD_NAV_FENCE_RETURN_POINT = 5000,
3137 #[doc = "Fence vertex for an inclusion polygon (the polygon must not be self-intersecting). The vehicle must stay within this area. Minimum of 3 vertices required. The vertices for a polygon must be sent sequentially, each with param1 set to the total number of vertices in the polygon."]
3138 #[doc = ""]
3139 #[doc = "# Parameters"]
3140 #[doc = ""]
3141 #[doc = "| Parameter | Description | Values |"]
3142 #[doc = "| --------- | ----------- | ------ |"]
3143 #[doc = "| 1 (Vertex Count)| Polygon vertex count. This is the number of vertices in the current polygon (all vertices will have the same number).| 3, 4, .. |"]
3144 #[doc = "| 2 (Inclusion Group)| Vehicle must be inside ALL inclusion zones in a single group, vehicle must be inside at least one group, must be the same for all points in each polygon| 0, 1, .. |"]
3145 #[doc = "| 3 | Reserved | |"]
3146 #[doc = "| 4 | Reserved | |"]
3147 #[doc = "| 5 (Latitude)| Latitude | |"]
3148 #[doc = "| 6 (Longitude)| Longitude | |"]
3149 #[doc = "| 7 | Reserved | |"]
3150 MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION = 5001,
3151 #[doc = "Fence vertex for an exclusion polygon (the polygon must not be self-intersecting). The vehicle must stay outside this area. Minimum of 3 vertices required. The vertices for a polygon must be sent sequentially, each with param1 set to the total number of vertices in the polygon."]
3152 #[doc = ""]
3153 #[doc = "# Parameters"]
3154 #[doc = ""]
3155 #[doc = "| Parameter | Description | Values |"]
3156 #[doc = "| --------- | ----------- | ------ |"]
3157 #[doc = "| 1 (Vertex Count)| Polygon vertex count. This is the number of vertices in the current polygon (all vertices will have the same number).| 3, 4, .. |"]
3158 #[doc = "| 2 | Reserved | |"]
3159 #[doc = "| 3 | Reserved | |"]
3160 #[doc = "| 4 | Reserved | |"]
3161 #[doc = "| 5 (Latitude)| Latitude | |"]
3162 #[doc = "| 6 (Longitude)| Longitude | |"]
3163 #[doc = "| 7 | Reserved | |"]
3164 MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION = 5002,
3165 #[doc = "Circular fence area. The vehicle must stay inside this area."]
3166 #[doc = ""]
3167 #[doc = "# Parameters"]
3168 #[doc = ""]
3169 #[doc = "| Parameter | Description | Values | Units |"]
3170 #[doc = "| --------- | ----------- | ------ | ----- |"]
3171 #[doc = "| 1 (Radius)| Radius. | | m |"]
3172 #[doc = "| 2 (Inclusion Group)| Vehicle must be inside ALL inclusion zones in a single group, vehicle must be inside at least one group| 0, 1, .. | |"]
3173 #[doc = "| 3 | Reserved | | |"]
3174 #[doc = "| 4 | Reserved | | |"]
3175 #[doc = "| 5 (Latitude)| Latitude | | |"]
3176 #[doc = "| 6 (Longitude)| Longitude | | |"]
3177 #[doc = "| 7 | Reserved | | |"]
3178 MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION = 5003,
3179 #[doc = "Circular fence area. The vehicle must stay outside this area."]
3180 #[doc = ""]
3181 #[doc = "# Parameters"]
3182 #[doc = ""]
3183 #[doc = "| Parameter | Description | Units |"]
3184 #[doc = "| --------- | ----------- | ----- |"]
3185 #[doc = "| 1 (Radius)| Radius. | m |"]
3186 #[doc = "| 2 | Reserved | |"]
3187 #[doc = "| 3 | Reserved | |"]
3188 #[doc = "| 4 | Reserved | |"]
3189 #[doc = "| 5 (Latitude)| Latitude | |"]
3190 #[doc = "| 6 (Longitude)| Longitude | |"]
3191 #[doc = "| 7 | Reserved | |"]
3192 MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION = 5004,
3193 #[doc = "Rally point. You can have multiple rally points defined."]
3194 #[doc = ""]
3195 #[doc = "# Parameters"]
3196 #[doc = ""]
3197 #[doc = "| Parameter | Description | Units |"]
3198 #[doc = "| --------- | ----------- | ----- |"]
3199 #[doc = "| 1 | Reserved | |"]
3200 #[doc = "| 2 | Reserved | |"]
3201 #[doc = "| 3 | Reserved | |"]
3202 #[doc = "| 4 | Reserved | |"]
3203 #[doc = "| 5 (Latitude)| Latitude | |"]
3204 #[doc = "| 6 (Longitude)| Longitude | |"]
3205 #[doc = "| 7 (Altitude)| Altitude | m |"]
3206 MAV_CMD_NAV_RALLY_POINT = 5100,
3207 #[doc = "Commands the vehicle to respond with a sequence of messages UAVCAN_NODE_INFO, one message per every UAVCAN node that is online. Note that some of the response messages can be lost, which the receiver can detect easily by checking whether every received UAVCAN_NODE_STATUS has a matching message UAVCAN_NODE_INFO received earlier; if not, this command should be sent again in order to request re-transmission of the node information messages."]
3208 #[doc = ""]
3209 #[doc = "# Parameters"]
3210 #[doc = ""]
3211 #[doc = "| Parameter | Description |"]
3212 #[doc = "| --------- | ----------- |"]
3213 #[doc = "| 1 | Reserved (set to 0)|"]
3214 #[doc = "| 2 | Reserved (set to 0)|"]
3215 #[doc = "| 3 | Reserved (set to 0)|"]
3216 #[doc = "| 4 | Reserved (set to 0)|"]
3217 #[doc = "| 5 | Reserved (set to 0)|"]
3218 #[doc = "| 6 | Reserved (set to 0)|"]
3219 #[doc = "| 7 | Reserved (set to 0)|"]
3220 MAV_CMD_UAVCAN_GET_NODE_INFO = 5200,
3221 #[doc = "Change state of safety switch."]
3222 #[doc = ""]
3223 #[doc = "# Parameters"]
3224 #[doc = ""]
3225 #[doc = "| Parameter | Description | Values |"]
3226 #[doc = "| --------- | ----------- | ------ |"]
3227 #[doc = "| 1 (Desired State)| New safety switch state.| [`SafetySwitchState`] |"]
3228 #[doc = "| 2 | Empty. | |"]
3229 #[doc = "| 3 | Empty. | |"]
3230 #[doc = "| 4 | Empty | |"]
3231 #[doc = "| 5 | Empty. | |"]
3232 #[doc = "| 6 | Empty. | |"]
3233 #[doc = "| 7 | Empty. | |"]
3234 MAV_CMD_DO_SET_SAFETY_SWITCH_STATE = 5300,
3235 #[doc = "Trigger the start of an ADSB-out IDENT. This should only be used when requested to do so by an Air Traffic Controller in controlled airspace. This starts the IDENT which is then typically held for 18 seconds by the hardware per the Mode A, C, and S transponder spec."]
3236 #[doc = ""]
3237 #[doc = "# Parameters"]
3238 #[doc = ""]
3239 #[doc = "| Parameter | Description |"]
3240 #[doc = "| --------- | ----------- |"]
3241 #[doc = "| 1 | Reserved (set to 0)|"]
3242 #[doc = "| 2 | Reserved (set to 0)|"]
3243 #[doc = "| 3 | Reserved (set to 0)|"]
3244 #[doc = "| 4 | Reserved (set to 0)|"]
3245 #[doc = "| 5 | Reserved (set to 0)|"]
3246 #[doc = "| 6 | Reserved (set to 0)|"]
3247 #[doc = "| 7 | Reserved (set to 0)|"]
3248 MAV_CMD_DO_ADSB_OUT_IDENT = 10001,
3249 #[deprecated = " (Deprecated since 2021-06)"]
3250 #[doc = "Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity."]
3251 #[doc = ""]
3252 #[doc = "# Parameters"]
3253 #[doc = ""]
3254 #[doc = "| Parameter | Description | Values | Units |"]
3255 #[doc = "| --------- | ----------- | ------ | ----- |"]
3256 #[doc = "| 1 (Operation Mode)| Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.| 0, 1, 2 | |"]
3257 #[doc = "| 2 (Approach Vector)| Desired approach vector in compass heading. A negative value indicates the system can define the approach vector at will.| -1 .. 360 | deg |"]
3258 #[doc = "| 3 (Ground Speed)| Desired ground speed at release time. This can be overridden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.| ≥ -1 | |"]
3259 #[doc = "| 4 (Altitude Clearance)| Minimum altitude clearance to the release position. A negative value indicates the system can define the clearance at will.| ≥ -1 | m |"]
3260 #[doc = "| 5 (Latitude)| Latitude. | | degE7 |"]
3261 #[doc = "| 6 (Longitude)| Longitude. | | degE7 |"]
3262 #[doc = "| 7 (Altitude)| Altitude (MSL)| | m |"]
3263 MAV_CMD_PAYLOAD_PREPARE_DEPLOY = 30001,
3264 #[deprecated = " (Deprecated since 2021-06)"]
3265 #[doc = "Control the payload deployment."]
3266 #[doc = ""]
3267 #[doc = "# Parameters"]
3268 #[doc = ""]
3269 #[doc = "| Parameter | Description | Values |"]
3270 #[doc = "| --------- | ----------- | ------ |"]
3271 #[doc = "| 1 (Operation Mode)| Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deployment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.| 0, 1, .. , 101 |"]
3272 #[doc = "| 2 | Reserved | |"]
3273 #[doc = "| 3 | Reserved | |"]
3274 #[doc = "| 4 | Reserved | |"]
3275 #[doc = "| 5 | Reserved | |"]
3276 #[doc = "| 6 | Reserved | |"]
3277 #[doc = "| 7 | Reserved | |"]
3278 MAV_CMD_PAYLOAD_CONTROL_DEPLOY = 30002,
3279 #[doc = "Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location."]
3280 #[doc = ""]
3281 #[doc = "# Parameters"]
3282 #[doc = ""]
3283 #[doc = "| Parameter | Description | Units |"]
3284 #[doc = "| --------- | ----------- | ----- |"]
3285 #[doc = "| 1 (Yaw) | Yaw of vehicle in earth frame.| deg |"]
3286 #[doc = "| 2 (CompassMask)| CompassMask, 0 for all.| |"]
3287 #[doc = "| 3 (Latitude)| Latitude. | deg |"]
3288 #[doc = "| 4 (Longitude)| Longitude. | deg |"]
3289 #[doc = "| 5 | Empty. | |"]
3290 #[doc = "| 6 | Empty. | |"]
3291 #[doc = "| 7 | Empty. | |"]
3292 MAV_CMD_FIXED_MAG_CAL_YAW = 42006,
3293 #[doc = "Command to operate winch."]
3294 #[doc = ""]
3295 #[doc = "# Parameters"]
3296 #[doc = ""]
3297 #[doc = "| Parameter | Description | Values | Units |"]
3298 #[doc = "| --------- | ----------- | ------ | ----- |"]
3299 #[doc = "| 1 (Instance)| Winch instance number.| 1, 2, .. | |"]
3300 #[doc = "| 2 (Action)| Action to perform.| [`WinchActions`] | |"]
3301 #[doc = "| 3 (Length)| Length of line to release (negative to wind).| | m |"]
3302 #[doc = "| 4 (Rate) | Release rate (negative to wind).| | m/s |"]
3303 #[doc = "| 5 | Empty. | | |"]
3304 #[doc = "| 6 | Empty. | | |"]
3305 #[doc = "| 7 | Empty. | | |"]
3306 MAV_CMD_DO_WINCH = 42600,
3307 #[doc = "Provide an external position estimate for use when dead-reckoning. This is meant to be used for occasional position resets that may be provided by a external system such as a remote pilot using landmarks over a video link."]
3308 #[doc = ""]
3309 #[doc = "# Parameters"]
3310 #[doc = ""]
3311 #[doc = "| Parameter | Description | Units |"]
3312 #[doc = "| --------- | ----------- | ----- |"]
3313 #[doc = "| 1 (transmission_time)| Timestamp that this message was sent as a time in the transmitters time domain. The sender should wrap this time back to zero based on required timing accuracy for the application and the limitations of a 32 bit float. For example, wrapping at 10 hours would give approximately 1ms accuracy. Recipient must handle time wrap in any timing jitter correction applied to this field. Wrap rollover time should not be at not more than 250 seconds, which would give approximately 10 microsecond accuracy.| s |"]
3314 #[doc = "| 2 (processing_time)| The time spent in processing the sensor data that is the basis for this position. The recipient can use this to improve time alignment of the data. Set to zero if not known.| s |"]
3315 #[doc = "| 3 (accuracy)| estimated one standard deviation accuracy of the measurement. Set to NaN if not known.| |"]
3316 #[doc = "| 4 | Empty | |"]
3317 #[doc = "| 5 (Latitude)| Latitude | |"]
3318 #[doc = "| 6 (Longitude)| Longitude | |"]
3319 #[doc = "| 7 (Altitude)| Altitude, not used. Should be sent as NaN. May be supported in a future version of this message.| m |"]
3320 MAV_CMD_EXTERNAL_POSITION_ESTIMATE = 43003,
3321 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
3322 #[doc = ""]
3323 #[doc = "# Parameters"]
3324 #[doc = ""]
3325 #[doc = "| Parameter | Description | Units |"]
3326 #[doc = "| --------- | ----------- | ----- |"]
3327 #[doc = "| 1 | User defined| |"]
3328 #[doc = "| 2 | User defined| |"]
3329 #[doc = "| 3 | User defined| |"]
3330 #[doc = "| 4 | User defined| |"]
3331 #[doc = "| 5 (Latitude)| Latitude unscaled| |"]
3332 #[doc = "| 6 (Longitude)| Longitude unscaled| |"]
3333 #[doc = "| 7 (Altitude)| Altitude (MSL)| m |"]
3334 MAV_CMD_WAYPOINT_USER_1 = 31000,
3335 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
3336 #[doc = ""]
3337 #[doc = "# Parameters"]
3338 #[doc = ""]
3339 #[doc = "| Parameter | Description | Units |"]
3340 #[doc = "| --------- | ----------- | ----- |"]
3341 #[doc = "| 1 | User defined| |"]
3342 #[doc = "| 2 | User defined| |"]
3343 #[doc = "| 3 | User defined| |"]
3344 #[doc = "| 4 | User defined| |"]
3345 #[doc = "| 5 (Latitude)| Latitude unscaled| |"]
3346 #[doc = "| 6 (Longitude)| Longitude unscaled| |"]
3347 #[doc = "| 7 (Altitude)| Altitude (MSL)| m |"]
3348 MAV_CMD_WAYPOINT_USER_2 = 31001,
3349 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
3350 #[doc = ""]
3351 #[doc = "# Parameters"]
3352 #[doc = ""]
3353 #[doc = "| Parameter | Description | Units |"]
3354 #[doc = "| --------- | ----------- | ----- |"]
3355 #[doc = "| 1 | User defined| |"]
3356 #[doc = "| 2 | User defined| |"]
3357 #[doc = "| 3 | User defined| |"]
3358 #[doc = "| 4 | User defined| |"]
3359 #[doc = "| 5 (Latitude)| Latitude unscaled| |"]
3360 #[doc = "| 6 (Longitude)| Longitude unscaled| |"]
3361 #[doc = "| 7 (Altitude)| Altitude (MSL)| m |"]
3362 MAV_CMD_WAYPOINT_USER_3 = 31002,
3363 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
3364 #[doc = ""]
3365 #[doc = "# Parameters"]
3366 #[doc = ""]
3367 #[doc = "| Parameter | Description | Units |"]
3368 #[doc = "| --------- | ----------- | ----- |"]
3369 #[doc = "| 1 | User defined| |"]
3370 #[doc = "| 2 | User defined| |"]
3371 #[doc = "| 3 | User defined| |"]
3372 #[doc = "| 4 | User defined| |"]
3373 #[doc = "| 5 (Latitude)| Latitude unscaled| |"]
3374 #[doc = "| 6 (Longitude)| Longitude unscaled| |"]
3375 #[doc = "| 7 (Altitude)| Altitude (MSL)| m |"]
3376 MAV_CMD_WAYPOINT_USER_4 = 31003,
3377 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
3378 #[doc = ""]
3379 #[doc = "# Parameters"]
3380 #[doc = ""]
3381 #[doc = "| Parameter | Description | Units |"]
3382 #[doc = "| --------- | ----------- | ----- |"]
3383 #[doc = "| 1 | User defined| |"]
3384 #[doc = "| 2 | User defined| |"]
3385 #[doc = "| 3 | User defined| |"]
3386 #[doc = "| 4 | User defined| |"]
3387 #[doc = "| 5 (Latitude)| Latitude unscaled| |"]
3388 #[doc = "| 6 (Longitude)| Longitude unscaled| |"]
3389 #[doc = "| 7 (Altitude)| Altitude (MSL)| m |"]
3390 MAV_CMD_WAYPOINT_USER_5 = 31004,
3391 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
3392 #[doc = ""]
3393 #[doc = "# Parameters"]
3394 #[doc = ""]
3395 #[doc = "| Parameter | Description | Units |"]
3396 #[doc = "| --------- | ----------- | ----- |"]
3397 #[doc = "| 1 | User defined| |"]
3398 #[doc = "| 2 | User defined| |"]
3399 #[doc = "| 3 | User defined| |"]
3400 #[doc = "| 4 | User defined| |"]
3401 #[doc = "| 5 (Latitude)| Latitude unscaled| |"]
3402 #[doc = "| 6 (Longitude)| Longitude unscaled| |"]
3403 #[doc = "| 7 (Altitude)| Altitude (MSL)| m |"]
3404 MAV_CMD_SPATIAL_USER_1 = 31005,
3405 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
3406 #[doc = ""]
3407 #[doc = "# Parameters"]
3408 #[doc = ""]
3409 #[doc = "| Parameter | Description | Units |"]
3410 #[doc = "| --------- | ----------- | ----- |"]
3411 #[doc = "| 1 | User defined| |"]
3412 #[doc = "| 2 | User defined| |"]
3413 #[doc = "| 3 | User defined| |"]
3414 #[doc = "| 4 | User defined| |"]
3415 #[doc = "| 5 (Latitude)| Latitude unscaled| |"]
3416 #[doc = "| 6 (Longitude)| Longitude unscaled| |"]
3417 #[doc = "| 7 (Altitude)| Altitude (MSL)| m |"]
3418 MAV_CMD_SPATIAL_USER_2 = 31006,
3419 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
3420 #[doc = ""]
3421 #[doc = "# Parameters"]
3422 #[doc = ""]
3423 #[doc = "| Parameter | Description | Units |"]
3424 #[doc = "| --------- | ----------- | ----- |"]
3425 #[doc = "| 1 | User defined| |"]
3426 #[doc = "| 2 | User defined| |"]
3427 #[doc = "| 3 | User defined| |"]
3428 #[doc = "| 4 | User defined| |"]
3429 #[doc = "| 5 (Latitude)| Latitude unscaled| |"]
3430 #[doc = "| 6 (Longitude)| Longitude unscaled| |"]
3431 #[doc = "| 7 (Altitude)| Altitude (MSL)| m |"]
3432 MAV_CMD_SPATIAL_USER_3 = 31007,
3433 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
3434 #[doc = ""]
3435 #[doc = "# Parameters"]
3436 #[doc = ""]
3437 #[doc = "| Parameter | Description | Units |"]
3438 #[doc = "| --------- | ----------- | ----- |"]
3439 #[doc = "| 1 | User defined| |"]
3440 #[doc = "| 2 | User defined| |"]
3441 #[doc = "| 3 | User defined| |"]
3442 #[doc = "| 4 | User defined| |"]
3443 #[doc = "| 5 (Latitude)| Latitude unscaled| |"]
3444 #[doc = "| 6 (Longitude)| Longitude unscaled| |"]
3445 #[doc = "| 7 (Altitude)| Altitude (MSL)| m |"]
3446 MAV_CMD_SPATIAL_USER_4 = 31008,
3447 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
3448 #[doc = ""]
3449 #[doc = "# Parameters"]
3450 #[doc = ""]
3451 #[doc = "| Parameter | Description | Units |"]
3452 #[doc = "| --------- | ----------- | ----- |"]
3453 #[doc = "| 1 | User defined| |"]
3454 #[doc = "| 2 | User defined| |"]
3455 #[doc = "| 3 | User defined| |"]
3456 #[doc = "| 4 | User defined| |"]
3457 #[doc = "| 5 (Latitude)| Latitude unscaled| |"]
3458 #[doc = "| 6 (Longitude)| Longitude unscaled| |"]
3459 #[doc = "| 7 (Altitude)| Altitude (MSL)| m |"]
3460 MAV_CMD_SPATIAL_USER_5 = 31009,
3461 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
3462 #[doc = ""]
3463 #[doc = "# Parameters"]
3464 #[doc = ""]
3465 #[doc = "| Parameter | Description |"]
3466 #[doc = "| --------- | ----------- |"]
3467 #[doc = "| 1 | User defined|"]
3468 #[doc = "| 2 | User defined|"]
3469 #[doc = "| 3 | User defined|"]
3470 #[doc = "| 4 | User defined|"]
3471 #[doc = "| 5 | User defined|"]
3472 #[doc = "| 6 | User defined|"]
3473 #[doc = "| 7 | User defined|"]
3474 MAV_CMD_USER_1 = 31010,
3475 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
3476 #[doc = ""]
3477 #[doc = "# Parameters"]
3478 #[doc = ""]
3479 #[doc = "| Parameter | Description |"]
3480 #[doc = "| --------- | ----------- |"]
3481 #[doc = "| 1 | User defined|"]
3482 #[doc = "| 2 | User defined|"]
3483 #[doc = "| 3 | User defined|"]
3484 #[doc = "| 4 | User defined|"]
3485 #[doc = "| 5 | User defined|"]
3486 #[doc = "| 6 | User defined|"]
3487 #[doc = "| 7 | User defined|"]
3488 MAV_CMD_USER_2 = 31011,
3489 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
3490 #[doc = ""]
3491 #[doc = "# Parameters"]
3492 #[doc = ""]
3493 #[doc = "| Parameter | Description |"]
3494 #[doc = "| --------- | ----------- |"]
3495 #[doc = "| 1 | User defined|"]
3496 #[doc = "| 2 | User defined|"]
3497 #[doc = "| 3 | User defined|"]
3498 #[doc = "| 4 | User defined|"]
3499 #[doc = "| 5 | User defined|"]
3500 #[doc = "| 6 | User defined|"]
3501 #[doc = "| 7 | User defined|"]
3502 MAV_CMD_USER_3 = 31012,
3503 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
3504 #[doc = ""]
3505 #[doc = "# Parameters"]
3506 #[doc = ""]
3507 #[doc = "| Parameter | Description |"]
3508 #[doc = "| --------- | ----------- |"]
3509 #[doc = "| 1 | User defined|"]
3510 #[doc = "| 2 | User defined|"]
3511 #[doc = "| 3 | User defined|"]
3512 #[doc = "| 4 | User defined|"]
3513 #[doc = "| 5 | User defined|"]
3514 #[doc = "| 6 | User defined|"]
3515 #[doc = "| 7 | User defined|"]
3516 MAV_CMD_USER_4 = 31013,
3517 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
3518 #[doc = ""]
3519 #[doc = "# Parameters"]
3520 #[doc = ""]
3521 #[doc = "| Parameter | Description |"]
3522 #[doc = "| --------- | ----------- |"]
3523 #[doc = "| 1 | User defined|"]
3524 #[doc = "| 2 | User defined|"]
3525 #[doc = "| 3 | User defined|"]
3526 #[doc = "| 4 | User defined|"]
3527 #[doc = "| 5 | User defined|"]
3528 #[doc = "| 6 | User defined|"]
3529 #[doc = "| 7 | User defined|"]
3530 MAV_CMD_USER_5 = 31014,
3531 #[doc = "Request forwarding of CAN packets from the given CAN bus to this component. CAN Frames are sent using CAN_FRAME and CANFD_FRAME messages"]
3532 #[doc = ""]
3533 #[doc = "# Parameters"]
3534 #[doc = ""]
3535 #[doc = "| Parameter | Description |"]
3536 #[doc = "| --------- | ----------- |"]
3537 #[doc = "| 1 (bus) | Bus number (0 to disable forwarding, 1 for first bus, 2 for 2nd bus, 3 for 3rd bus).|"]
3538 #[doc = "| 2 | Empty. |"]
3539 #[doc = "| 3 | Empty. |"]
3540 #[doc = "| 4 | Empty. |"]
3541 #[doc = "| 5 | Empty. |"]
3542 #[doc = "| 6 | Empty. |"]
3543 #[doc = "| 7 | Empty. |"]
3544 MAV_CMD_CAN_FORWARD = 32000,
3545}
3546impl MavCmd {
3547 pub const DEFAULT: Self = Self::MAV_CMD_NAV_WAYPOINT;
3548}
3549impl Default for MavCmd {
3550 fn default() -> Self {
3551 Self::DEFAULT
3552 }
3553}
3554#[cfg_attr(feature = "ts", derive(TS))]
3555#[cfg_attr(feature = "ts", ts(export))]
3556#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3557#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3558#[cfg_attr(feature = "serde", serde(tag = "type"))]
3559#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3560#[repr(u32)]
3561#[doc = "Possible actions an aircraft can take to avoid a collision."]
3562pub enum MavCollisionAction {
3563 #[doc = "Ignore any potential collisions"]
3564 MAV_COLLISION_ACTION_NONE = 0,
3565 #[doc = "Report potential collision"]
3566 MAV_COLLISION_ACTION_REPORT = 1,
3567 #[doc = "Ascend or Descend to avoid threat"]
3568 MAV_COLLISION_ACTION_ASCEND_OR_DESCEND = 2,
3569 #[doc = "Move horizontally to avoid threat"]
3570 MAV_COLLISION_ACTION_MOVE_HORIZONTALLY = 3,
3571 #[doc = "Aircraft to move perpendicular to the collision's velocity vector"]
3572 MAV_COLLISION_ACTION_MOVE_PERPENDICULAR = 4,
3573 #[doc = "Aircraft to fly directly back to its launch point"]
3574 MAV_COLLISION_ACTION_RTL = 5,
3575 #[doc = "Aircraft to stop in place"]
3576 MAV_COLLISION_ACTION_HOVER = 6,
3577}
3578impl MavCollisionAction {
3579 pub const DEFAULT: Self = Self::MAV_COLLISION_ACTION_NONE;
3580}
3581impl Default for MavCollisionAction {
3582 fn default() -> Self {
3583 Self::DEFAULT
3584 }
3585}
3586#[cfg_attr(feature = "ts", derive(TS))]
3587#[cfg_attr(feature = "ts", ts(export))]
3588#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3589#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3590#[cfg_attr(feature = "serde", serde(tag = "type"))]
3591#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3592#[repr(u32)]
3593#[doc = "Source of information about this collision."]
3594pub enum MavCollisionSrc {
3595 #[doc = "ID field references ADSB_VEHICLE packets"]
3596 MAV_COLLISION_SRC_ADSB = 0,
3597 #[doc = "ID field references MAVLink SRC ID"]
3598 MAV_COLLISION_SRC_MAVLINK_GPS_GLOBAL_INT = 1,
3599}
3600impl MavCollisionSrc {
3601 pub const DEFAULT: Self = Self::MAV_COLLISION_SRC_ADSB;
3602}
3603impl Default for MavCollisionSrc {
3604 fn default() -> Self {
3605 Self::DEFAULT
3606 }
3607}
3608#[cfg_attr(feature = "ts", derive(TS))]
3609#[cfg_attr(feature = "ts", ts(export))]
3610#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3611#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3612#[cfg_attr(feature = "serde", serde(tag = "type"))]
3613#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3614#[repr(u32)]
3615#[doc = "Aircraft-rated danger from this threat."]
3616pub enum MavCollisionThreatLevel {
3617 #[doc = "Not a threat"]
3618 MAV_COLLISION_THREAT_LEVEL_NONE = 0,
3619 #[doc = "Craft is mildly concerned about this threat"]
3620 MAV_COLLISION_THREAT_LEVEL_LOW = 1,
3621 #[doc = "Craft is panicking, and may take actions to avoid threat"]
3622 MAV_COLLISION_THREAT_LEVEL_HIGH = 2,
3623}
3624impl MavCollisionThreatLevel {
3625 pub const DEFAULT: Self = Self::MAV_COLLISION_THREAT_LEVEL_NONE;
3626}
3627impl Default for MavCollisionThreatLevel {
3628 fn default() -> Self {
3629 Self::DEFAULT
3630 }
3631}
3632#[cfg_attr(feature = "ts", derive(TS))]
3633#[cfg_attr(feature = "ts", ts(export))]
3634#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3635#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3636#[cfg_attr(feature = "serde", serde(tag = "type"))]
3637#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3638#[repr(u32)]
3639#[doc = "Component ids (values) for the different types and instances of onboard hardware/software that might make up a MAVLink system (autopilot, cameras, servos, GPS systems, avoidance systems etc.). Components must use the appropriate ID in their source address when sending messages. Components can also use IDs to determine if they are the intended recipient of an incoming message. The MAV_COMP_ID_ALL value is used to indicate messages that must be processed by all components. When creating new entries, components that can have multiple instances (e.g. cameras, servos etc.) should be allocated sequential values. An appropriate number of values should be left free after these components to allow the number of instances to be expanded."]
3640pub enum MavComponent {
3641 #[doc = "Target id (target_component) used to broadcast messages to all components of the receiving system. Components should attempt to process messages with this component ID and forward to components on any other interfaces. Note: This is not a valid *source* component id for a message."]
3642 MAV_COMP_ID_ALL = 0,
3643 #[doc = "System flight controller component (\"autopilot\"). Only one autopilot is expected in a particular system."]
3644 MAV_COMP_ID_AUTOPILOT1 = 1,
3645 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3646 MAV_COMP_ID_USER1 = 25,
3647 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3648 MAV_COMP_ID_USER2 = 26,
3649 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3650 MAV_COMP_ID_USER3 = 27,
3651 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3652 MAV_COMP_ID_USER4 = 28,
3653 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3654 MAV_COMP_ID_USER5 = 29,
3655 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3656 MAV_COMP_ID_USER6 = 30,
3657 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3658 MAV_COMP_ID_USER7 = 31,
3659 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3660 MAV_COMP_ID_USER8 = 32,
3661 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3662 MAV_COMP_ID_USER9 = 33,
3663 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3664 MAV_COMP_ID_USER10 = 34,
3665 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3666 MAV_COMP_ID_USER11 = 35,
3667 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3668 MAV_COMP_ID_USER12 = 36,
3669 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3670 MAV_COMP_ID_USER13 = 37,
3671 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3672 MAV_COMP_ID_USER14 = 38,
3673 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3674 MAV_COMP_ID_USER15 = 39,
3675 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3676 MAV_COMP_ID_USER16 = 40,
3677 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3678 MAV_COMP_ID_USER17 = 41,
3679 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3680 MAV_COMP_ID_USER18 = 42,
3681 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3682 MAV_COMP_ID_USER19 = 43,
3683 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3684 MAV_COMP_ID_USER20 = 44,
3685 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3686 MAV_COMP_ID_USER21 = 45,
3687 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3688 MAV_COMP_ID_USER22 = 46,
3689 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3690 MAV_COMP_ID_USER23 = 47,
3691 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3692 MAV_COMP_ID_USER24 = 48,
3693 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3694 MAV_COMP_ID_USER25 = 49,
3695 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3696 MAV_COMP_ID_USER26 = 50,
3697 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3698 MAV_COMP_ID_USER27 = 51,
3699 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3700 MAV_COMP_ID_USER28 = 52,
3701 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3702 MAV_COMP_ID_USER29 = 53,
3703 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3704 MAV_COMP_ID_USER30 = 54,
3705 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3706 MAV_COMP_ID_USER31 = 55,
3707 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3708 MAV_COMP_ID_USER32 = 56,
3709 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3710 MAV_COMP_ID_USER33 = 57,
3711 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3712 MAV_COMP_ID_USER34 = 58,
3713 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3714 MAV_COMP_ID_USER35 = 59,
3715 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3716 MAV_COMP_ID_USER36 = 60,
3717 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3718 MAV_COMP_ID_USER37 = 61,
3719 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3720 MAV_COMP_ID_USER38 = 62,
3721 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3722 MAV_COMP_ID_USER39 = 63,
3723 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3724 MAV_COMP_ID_USER40 = 64,
3725 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3726 MAV_COMP_ID_USER41 = 65,
3727 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3728 MAV_COMP_ID_USER42 = 66,
3729 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3730 MAV_COMP_ID_USER43 = 67,
3731 #[doc = "Telemetry radio (e.g. SiK radio, or other component that emits RADIO_STATUS messages)."]
3732 MAV_COMP_ID_TELEMETRY_RADIO = 68,
3733 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3734 MAV_COMP_ID_USER45 = 69,
3735 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3736 MAV_COMP_ID_USER46 = 70,
3737 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3738 MAV_COMP_ID_USER47 = 71,
3739 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3740 MAV_COMP_ID_USER48 = 72,
3741 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3742 MAV_COMP_ID_USER49 = 73,
3743 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3744 MAV_COMP_ID_USER50 = 74,
3745 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3746 MAV_COMP_ID_USER51 = 75,
3747 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3748 MAV_COMP_ID_USER52 = 76,
3749 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3750 MAV_COMP_ID_USER53 = 77,
3751 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3752 MAV_COMP_ID_USER54 = 78,
3753 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3754 MAV_COMP_ID_USER55 = 79,
3755 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3756 MAV_COMP_ID_USER56 = 80,
3757 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3758 MAV_COMP_ID_USER57 = 81,
3759 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3760 MAV_COMP_ID_USER58 = 82,
3761 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3762 MAV_COMP_ID_USER59 = 83,
3763 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3764 MAV_COMP_ID_USER60 = 84,
3765 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3766 MAV_COMP_ID_USER61 = 85,
3767 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3768 MAV_COMP_ID_USER62 = 86,
3769 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3770 MAV_COMP_ID_USER63 = 87,
3771 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3772 MAV_COMP_ID_USER64 = 88,
3773 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3774 MAV_COMP_ID_USER65 = 89,
3775 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3776 MAV_COMP_ID_USER66 = 90,
3777 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3778 MAV_COMP_ID_USER67 = 91,
3779 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3780 MAV_COMP_ID_USER68 = 92,
3781 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3782 MAV_COMP_ID_USER69 = 93,
3783 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3784 MAV_COMP_ID_USER70 = 94,
3785 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3786 MAV_COMP_ID_USER71 = 95,
3787 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3788 MAV_COMP_ID_USER72 = 96,
3789 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3790 MAV_COMP_ID_USER73 = 97,
3791 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3792 MAV_COMP_ID_USER74 = 98,
3793 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
3794 MAV_COMP_ID_USER75 = 99,
3795 #[doc = "Camera #1."]
3796 MAV_COMP_ID_CAMERA = 100,
3797 #[doc = "Camera #2."]
3798 MAV_COMP_ID_CAMERA2 = 101,
3799 #[doc = "Camera #3."]
3800 MAV_COMP_ID_CAMERA3 = 102,
3801 #[doc = "Camera #4."]
3802 MAV_COMP_ID_CAMERA4 = 103,
3803 #[doc = "Camera #5."]
3804 MAV_COMP_ID_CAMERA5 = 104,
3805 #[doc = "Camera #6."]
3806 MAV_COMP_ID_CAMERA6 = 105,
3807 #[doc = "Servo #1."]
3808 MAV_COMP_ID_SERVO1 = 140,
3809 #[doc = "Servo #2."]
3810 MAV_COMP_ID_SERVO2 = 141,
3811 #[doc = "Servo #3."]
3812 MAV_COMP_ID_SERVO3 = 142,
3813 #[doc = "Servo #4."]
3814 MAV_COMP_ID_SERVO4 = 143,
3815 #[doc = "Servo #5."]
3816 MAV_COMP_ID_SERVO5 = 144,
3817 #[doc = "Servo #6."]
3818 MAV_COMP_ID_SERVO6 = 145,
3819 #[doc = "Servo #7."]
3820 MAV_COMP_ID_SERVO7 = 146,
3821 #[doc = "Servo #8."]
3822 MAV_COMP_ID_SERVO8 = 147,
3823 #[doc = "Servo #9."]
3824 MAV_COMP_ID_SERVO9 = 148,
3825 #[doc = "Servo #10."]
3826 MAV_COMP_ID_SERVO10 = 149,
3827 #[doc = "Servo #11."]
3828 MAV_COMP_ID_SERVO11 = 150,
3829 #[doc = "Servo #12."]
3830 MAV_COMP_ID_SERVO12 = 151,
3831 #[doc = "Servo #13."]
3832 MAV_COMP_ID_SERVO13 = 152,
3833 #[doc = "Servo #14."]
3834 MAV_COMP_ID_SERVO14 = 153,
3835 #[doc = "Gimbal #1."]
3836 MAV_COMP_ID_GIMBAL = 154,
3837 #[doc = "Logging component."]
3838 MAV_COMP_ID_LOG = 155,
3839 #[doc = "Automatic Dependent Surveillance-Broadcast (ADS-B) component."]
3840 MAV_COMP_ID_ADSB = 156,
3841 #[doc = "On Screen Display (OSD) devices for video links."]
3842 MAV_COMP_ID_OSD = 157,
3843 #[doc = "Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter microservice."]
3844 MAV_COMP_ID_PERIPHERAL = 158,
3845 #[deprecated = "All gimbals should use MAV_COMP_ID_GIMBAL. See `MAV_COMP_ID_GIMBAL` (Deprecated since 2018-11)"]
3846 #[doc = "Gimbal ID for QX1."]
3847 MAV_COMP_ID_QX1_GIMBAL = 159,
3848 #[doc = "FLARM collision alert component."]
3849 MAV_COMP_ID_FLARM = 160,
3850 #[doc = "Parachute component."]
3851 MAV_COMP_ID_PARACHUTE = 161,
3852 #[doc = "Winch component."]
3853 MAV_COMP_ID_WINCH = 169,
3854 #[doc = "Gimbal #2."]
3855 MAV_COMP_ID_GIMBAL2 = 171,
3856 #[doc = "Gimbal #3."]
3857 MAV_COMP_ID_GIMBAL3 = 172,
3858 #[doc = "Gimbal #4"]
3859 MAV_COMP_ID_GIMBAL4 = 173,
3860 #[doc = "Gimbal #5."]
3861 MAV_COMP_ID_GIMBAL5 = 174,
3862 #[doc = "Gimbal #6."]
3863 MAV_COMP_ID_GIMBAL6 = 175,
3864 #[doc = "Battery #1."]
3865 MAV_COMP_ID_BATTERY = 180,
3866 #[doc = "Battery #2."]
3867 MAV_COMP_ID_BATTERY2 = 181,
3868 #[doc = "CAN over MAVLink client."]
3869 MAV_COMP_ID_MAVCAN = 189,
3870 #[doc = "Component that can generate/supply a mission flight plan (e.g. GCS or developer API)."]
3871 MAV_COMP_ID_MISSIONPLANNER = 190,
3872 #[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
3873 MAV_COMP_ID_ONBOARD_COMPUTER = 191,
3874 #[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
3875 MAV_COMP_ID_ONBOARD_COMPUTER2 = 192,
3876 #[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
3877 MAV_COMP_ID_ONBOARD_COMPUTER3 = 193,
3878 #[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
3879 MAV_COMP_ID_ONBOARD_COMPUTER4 = 194,
3880 #[doc = "Component that finds an optimal path between points based on a certain constraint (e.g. minimum snap, shortest path, cost, etc.)."]
3881 MAV_COMP_ID_PATHPLANNER = 195,
3882 #[doc = "Component that plans a collision free path between two points."]
3883 MAV_COMP_ID_OBSTACLE_AVOIDANCE = 196,
3884 #[doc = "Component that provides position estimates using VIO techniques."]
3885 MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY = 197,
3886 #[doc = "Component that manages pairing of vehicle and GCS."]
3887 MAV_COMP_ID_PAIRING_MANAGER = 198,
3888 #[doc = "Inertial Measurement Unit (IMU) #1."]
3889 MAV_COMP_ID_IMU = 200,
3890 #[doc = "Inertial Measurement Unit (IMU) #2."]
3891 MAV_COMP_ID_IMU_2 = 201,
3892 #[doc = "Inertial Measurement Unit (IMU) #3."]
3893 MAV_COMP_ID_IMU_3 = 202,
3894 #[doc = "GPS #1."]
3895 MAV_COMP_ID_GPS = 220,
3896 #[doc = "GPS #2."]
3897 MAV_COMP_ID_GPS2 = 221,
3898 #[doc = "Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet)."]
3899 MAV_COMP_ID_ODID_TXRX_1 = 236,
3900 #[doc = "Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet)."]
3901 MAV_COMP_ID_ODID_TXRX_2 = 237,
3902 #[doc = "Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet)."]
3903 MAV_COMP_ID_ODID_TXRX_3 = 238,
3904 #[doc = "Component to bridge MAVLink to UDP (i.e. from a UART)."]
3905 MAV_COMP_ID_UDP_BRIDGE = 240,
3906 #[doc = "Component to bridge to UART (i.e. from UDP)."]
3907 MAV_COMP_ID_UART_BRIDGE = 241,
3908 #[doc = "Component handling TUNNEL messages (e.g. vendor specific GUI of a component)."]
3909 MAV_COMP_ID_TUNNEL_NODE = 242,
3910 #[doc = "Illuminator"]
3911 MAV_COMP_ID_ILLUMINATOR = 243,
3912 #[deprecated = "System control does not require a separate component ID. Instead, system commands should be sent with target_component=MAV_COMP_ID_ALL allowing the target component to use any appropriate component id. See `MAV_COMP_ID_ALL` (Deprecated since 2018-11)"]
3913 #[doc = "Deprecated, don't use. Component for handling system messages (e.g. to ARM, takeoff, etc.)."]
3914 MAV_COMP_ID_SYSTEM_CONTROL = 250,
3915}
3916impl MavComponent {
3917 pub const DEFAULT: Self = Self::MAV_COMP_ID_ALL;
3918}
3919impl Default for MavComponent {
3920 fn default() -> Self {
3921 Self::DEFAULT
3922 }
3923}
3924#[cfg_attr(feature = "ts", derive(TS))]
3925#[cfg_attr(feature = "ts", ts(export))]
3926#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3927#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3928#[cfg_attr(feature = "serde", serde(tag = "type"))]
3929#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3930#[repr(u32)]
3931#[deprecated = " See `MESSAGE_INTERVAL` (Deprecated since 2015-06)"]
3932#[doc = "A data stream is not a fixed set of messages, but rather a recommendation to the autopilot software. Individual autopilots may or may not obey the recommended messages."]
3933pub enum MavDataStream {
3934 #[doc = "Enable all data streams"]
3935 MAV_DATA_STREAM_ALL = 0,
3936 #[doc = "Enable IMU_RAW, GPS_RAW, GPS_STATUS packets."]
3937 MAV_DATA_STREAM_RAW_SENSORS = 1,
3938 #[doc = "Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS"]
3939 MAV_DATA_STREAM_EXTENDED_STATUS = 2,
3940 #[doc = "Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW"]
3941 MAV_DATA_STREAM_RC_CHANNELS = 3,
3942 #[doc = "Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT."]
3943 MAV_DATA_STREAM_RAW_CONTROLLER = 4,
3944 #[doc = "Enable LOCAL_POSITION, GLOBAL_POSITION_INT messages."]
3945 MAV_DATA_STREAM_POSITION = 6,
3946 #[doc = "Dependent on the autopilot"]
3947 MAV_DATA_STREAM_EXTRA1 = 10,
3948 #[doc = "Dependent on the autopilot"]
3949 MAV_DATA_STREAM_EXTRA2 = 11,
3950 #[doc = "Dependent on the autopilot"]
3951 MAV_DATA_STREAM_EXTRA3 = 12,
3952}
3953impl MavDataStream {
3954 pub const DEFAULT: Self = Self::MAV_DATA_STREAM_ALL;
3955}
3956impl Default for MavDataStream {
3957 fn default() -> Self {
3958 Self::DEFAULT
3959 }
3960}
3961#[cfg_attr(feature = "ts", derive(TS))]
3962#[cfg_attr(feature = "ts", ts(export))]
3963#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3964#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3965#[cfg_attr(feature = "serde", serde(tag = "type"))]
3966#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3967#[repr(u32)]
3968#[doc = "Enumeration of distance sensor types"]
3969pub enum MavDistanceSensor {
3970 #[doc = "Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units"]
3971 MAV_DISTANCE_SENSOR_LASER = 0,
3972 #[doc = "Ultrasound rangefinder, e.g. MaxBotix units"]
3973 MAV_DISTANCE_SENSOR_ULTRASOUND = 1,
3974 #[doc = "Infrared rangefinder, e.g. Sharp units"]
3975 MAV_DISTANCE_SENSOR_INFRARED = 2,
3976 #[doc = "Radar type, e.g. uLanding units"]
3977 MAV_DISTANCE_SENSOR_RADAR = 3,
3978 #[doc = "Broken or unknown type, e.g. analog units"]
3979 MAV_DISTANCE_SENSOR_UNKNOWN = 4,
3980}
3981impl MavDistanceSensor {
3982 pub const DEFAULT: Self = Self::MAV_DISTANCE_SENSOR_LASER;
3983}
3984impl Default for MavDistanceSensor {
3985 fn default() -> Self {
3986 Self::DEFAULT
3987 }
3988}
3989#[cfg_attr(feature = "ts", derive(TS))]
3990#[cfg_attr(feature = "ts", ts(export))]
3991#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3992#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3993#[cfg_attr(feature = "serde", serde(tag = "type"))]
3994#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3995#[repr(u32)]
3996#[doc = "Bitmap of options for the MAV_CMD_DO_REPOSITION"]
3997pub enum MavDoRepositionFlags {
3998 #[doc = "The aircraft should immediately transition into guided. This should not be set for follow me applications"]
3999 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE = 1,
4000}
4001impl MavDoRepositionFlags {
4002 pub const DEFAULT: Self = Self::MAV_DO_REPOSITION_FLAGS_CHANGE_MODE;
4003}
4004impl Default for MavDoRepositionFlags {
4005 fn default() -> Self {
4006 Self::DEFAULT
4007 }
4008}
4009#[cfg_attr(feature = "ts", derive(TS))]
4010#[cfg_attr(feature = "ts", ts(export))]
4011#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4012#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4013#[cfg_attr(feature = "serde", serde(tag = "type"))]
4014#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4015#[repr(u32)]
4016#[doc = "Enumeration of estimator types"]
4017pub enum MavEstimatorType {
4018 #[doc = "Unknown type of the estimator."]
4019 MAV_ESTIMATOR_TYPE_UNKNOWN = 0,
4020 #[doc = "This is a naive estimator without any real covariance feedback."]
4021 MAV_ESTIMATOR_TYPE_NAIVE = 1,
4022 #[doc = "Computer vision based estimate. Might be up to scale."]
4023 MAV_ESTIMATOR_TYPE_VISION = 2,
4024 #[doc = "Visual-inertial estimate."]
4025 MAV_ESTIMATOR_TYPE_VIO = 3,
4026 #[doc = "Plain GPS estimate."]
4027 MAV_ESTIMATOR_TYPE_GPS = 4,
4028 #[doc = "Estimator integrating GPS and inertial sensing."]
4029 MAV_ESTIMATOR_TYPE_GPS_INS = 5,
4030 #[doc = "Estimate from external motion capturing system."]
4031 MAV_ESTIMATOR_TYPE_MOCAP = 6,
4032 #[doc = "Estimator based on lidar sensor input."]
4033 MAV_ESTIMATOR_TYPE_LIDAR = 7,
4034 #[doc = "Estimator on autopilot."]
4035 MAV_ESTIMATOR_TYPE_AUTOPILOT = 8,
4036}
4037impl MavEstimatorType {
4038 pub const DEFAULT: Self = Self::MAV_ESTIMATOR_TYPE_UNKNOWN;
4039}
4040impl Default for MavEstimatorType {
4041 fn default() -> Self {
4042 Self::DEFAULT
4043 }
4044}
4045#[cfg_attr(feature = "ts", derive(TS))]
4046#[cfg_attr(feature = "ts", ts(export))]
4047#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4048#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4049#[cfg_attr(feature = "serde", serde(tag = "type"))]
4050#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4051#[repr(u32)]
4052#[doc = "Flags for CURRENT_EVENT_SEQUENCE."]
4053pub enum MavEventCurrentSequenceFlags {
4054 #[doc = "A sequence reset has happened (e.g. vehicle reboot)."]
4055 MAV_EVENT_CURRENT_SEQUENCE_FLAGS_RESET = 1,
4056}
4057impl MavEventCurrentSequenceFlags {
4058 pub const DEFAULT: Self = Self::MAV_EVENT_CURRENT_SEQUENCE_FLAGS_RESET;
4059}
4060impl Default for MavEventCurrentSequenceFlags {
4061 fn default() -> Self {
4062 Self::DEFAULT
4063 }
4064}
4065#[cfg_attr(feature = "ts", derive(TS))]
4066#[cfg_attr(feature = "ts", ts(export))]
4067#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4068#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4069#[cfg_attr(feature = "serde", serde(tag = "type"))]
4070#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4071#[repr(u32)]
4072#[doc = "Reason for an event error response."]
4073pub enum MavEventErrorReason {
4074 #[doc = "The requested event is not available (anymore)."]
4075 MAV_EVENT_ERROR_REASON_UNAVAILABLE = 0,
4076}
4077impl MavEventErrorReason {
4078 pub const DEFAULT: Self = Self::MAV_EVENT_ERROR_REASON_UNAVAILABLE;
4079}
4080impl Default for MavEventErrorReason {
4081 fn default() -> Self {
4082 Self::DEFAULT
4083 }
4084}
4085#[cfg_attr(feature = "ts", derive(TS))]
4086#[cfg_attr(feature = "ts", ts(export))]
4087#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4088#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4089#[cfg_attr(feature = "serde", serde(tag = "type"))]
4090#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4091#[repr(u32)]
4092#[doc = "Coordinate frames used by MAVLink. Not all frames are supported by all commands, messages, or vehicles. Global frames use the following naming conventions: - \"GLOBAL\": Global coordinate frame with WGS84 latitude/longitude and altitude positive over mean sea level (MSL) by default. The following modifiers may be used with \"GLOBAL\": - \"RELATIVE_ALT\": Altitude is relative to the vehicle home position rather than MSL. - \"TERRAIN_ALT\": Altitude is relative to ground level rather than MSL. - \"INT\": Latitude/longitude (in degrees) are scaled by multiplying by 1E7. Local frames use the following naming conventions: - \"LOCAL\": Origin of local frame is fixed relative to earth. Unless otherwise specified this origin is the origin of the vehicle position-estimator (\"EKF\"). - \"BODY\": Origin of local frame travels with the vehicle. NOTE, \"BODY\" does NOT indicate alignment of frame axis with vehicle attitude. - \"OFFSET\": Deprecated synonym for \"BODY\" (origin travels with the vehicle). Not to be used for new frames. Some deprecated frames do not follow these conventions (e.g. MAV_FRAME_BODY_NED and MAV_FRAME_BODY_OFFSET_NED)."]
4093pub enum MavFrame {
4094 #[doc = "Global (WGS84) coordinate frame + altitude relative to mean sea level (MSL)."]
4095 MAV_FRAME_GLOBAL = 0,
4096 #[doc = "NED local tangent frame (x: North, y: East, z: Down) with origin fixed relative to earth."]
4097 MAV_FRAME_LOCAL_NED = 1,
4098 #[doc = "NOT a coordinate frame, indicates a mission command."]
4099 MAV_FRAME_MISSION = 2,
4100 #[doc = "Global (WGS84) coordinate frame + altitude relative to the home position."]
4101 MAV_FRAME_GLOBAL_RELATIVE_ALT = 3,
4102 #[doc = "ENU local tangent frame (x: East, y: North, z: Up) with origin fixed relative to earth."]
4103 MAV_FRAME_LOCAL_ENU = 4,
4104 #[deprecated = "Use MAV_FRAME_GLOBAL in COMMAND_INT (and elsewhere) as a synonymous replacement. See `MAV_FRAME_GLOBAL` (Deprecated since 2024-03)"]
4105 #[doc = "Global (WGS84) coordinate frame (scaled) + altitude relative to mean sea level (MSL)."]
4106 MAV_FRAME_GLOBAL_INT = 5,
4107 #[deprecated = "Use MAV_FRAME_GLOBAL_RELATIVE_ALT in COMMAND_INT (and elsewhere) as a synonymous replacement. See `MAV_FRAME_GLOBAL_RELATIVE_ALT` (Deprecated since 2024-03)"]
4108 #[doc = "Global (WGS84) coordinate frame (scaled) + altitude relative to the home position."]
4109 MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6,
4110 #[doc = "NED local tangent frame (x: North, y: East, z: Down) with origin that travels with the vehicle."]
4111 MAV_FRAME_LOCAL_OFFSET_NED = 7,
4112 #[deprecated = " See `MAV_FRAME_BODY_FRD` (Deprecated since 2019-08)"]
4113 #[doc = "Same as MAV_FRAME_LOCAL_NED when used to represent position values. Same as MAV_FRAME_BODY_FRD when used with velocity/acceleration values."]
4114 MAV_FRAME_BODY_NED = 8,
4115 #[deprecated = " See `MAV_FRAME_BODY_FRD` (Deprecated since 2019-08)"]
4116 #[doc = "This is the same as MAV_FRAME_BODY_FRD."]
4117 MAV_FRAME_BODY_OFFSET_NED = 9,
4118 #[doc = "Global (WGS84) coordinate frame with AGL altitude (altitude at ground level)."]
4119 MAV_FRAME_GLOBAL_TERRAIN_ALT = 10,
4120 #[deprecated = "Use MAV_FRAME_GLOBAL_TERRAIN_ALT in COMMAND_INT (and elsewhere) as a synonymous replacement. See `MAV_FRAME_GLOBAL_TERRAIN_ALT` (Deprecated since 2024-03)"]
4121 #[doc = "Global (WGS84) coordinate frame (scaled) with AGL altitude (altitude at ground level)."]
4122 MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11,
4123 #[doc = "FRD local frame aligned to the vehicle's attitude (x: Forward, y: Right, z: Down) with an origin that travels with vehicle."]
4124 MAV_FRAME_BODY_FRD = 12,
4125 #[deprecated = " (Deprecated since 2019-04)"]
4126 #[doc = "MAV_FRAME_BODY_FLU - Body fixed frame of reference, Z-up (x: Forward, y: Left, z: Up)."]
4127 MAV_FRAME_RESERVED_13 = 13,
4128 #[deprecated = " See `MAV_FRAME_LOCAL_FRD` (Deprecated since 2019-04)"]
4129 #[doc = "MAV_FRAME_MOCAP_NED - Odometry local coordinate frame of data given by a motion capture system, Z-down (x: North, y: East, z: Down)."]
4130 MAV_FRAME_RESERVED_14 = 14,
4131 #[deprecated = " See `MAV_FRAME_LOCAL_FLU` (Deprecated since 2019-04)"]
4132 #[doc = "MAV_FRAME_MOCAP_ENU - Odometry local coordinate frame of data given by a motion capture system, Z-up (x: East, y: North, z: Up)."]
4133 MAV_FRAME_RESERVED_15 = 15,
4134 #[deprecated = " See `MAV_FRAME_LOCAL_FRD` (Deprecated since 2019-04)"]
4135 #[doc = "MAV_FRAME_VISION_NED - Odometry local coordinate frame of data given by a vision estimation system, Z-down (x: North, y: East, z: Down)."]
4136 MAV_FRAME_RESERVED_16 = 16,
4137 #[deprecated = " See `MAV_FRAME_LOCAL_FLU` (Deprecated since 2019-04)"]
4138 #[doc = "MAV_FRAME_VISION_ENU - Odometry local coordinate frame of data given by a vision estimation system, Z-up (x: East, y: North, z: Up)."]
4139 MAV_FRAME_RESERVED_17 = 17,
4140 #[deprecated = " See `MAV_FRAME_LOCAL_FRD` (Deprecated since 2019-04)"]
4141 #[doc = "MAV_FRAME_ESTIM_NED - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: North, y: East, z: Down)."]
4142 MAV_FRAME_RESERVED_18 = 18,
4143 #[deprecated = " See `MAV_FRAME_LOCAL_FLU` (Deprecated since 2019-04)"]
4144 #[doc = "MAV_FRAME_ESTIM_ENU - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-up (x: East, y: North, z: Up)."]
4145 MAV_FRAME_RESERVED_19 = 19,
4146 #[doc = "FRD local tangent frame (x: Forward, y: Right, z: Down) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane."]
4147 MAV_FRAME_LOCAL_FRD = 20,
4148 #[doc = "FLU local tangent frame (x: Forward, y: Left, z: Up) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane."]
4149 MAV_FRAME_LOCAL_FLU = 21,
4150}
4151impl MavFrame {
4152 pub const DEFAULT: Self = Self::MAV_FRAME_GLOBAL;
4153}
4154impl Default for MavFrame {
4155 fn default() -> Self {
4156 Self::DEFAULT
4157 }
4158}
4159#[cfg_attr(feature = "ts", derive(TS))]
4160#[cfg_attr(feature = "ts", ts(export))]
4161#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4162#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4163#[cfg_attr(feature = "serde", serde(tag = "type"))]
4164#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4165#[repr(u32)]
4166#[doc = "MAV FTP error codes (<https://mavlink.io/en/services/ftp.html>)"]
4167pub enum MavFtpErr {
4168 #[doc = "None: No error"]
4169 MAV_FTP_ERR_NONE = 0,
4170 #[doc = "Fail: Unknown failure"]
4171 MAV_FTP_ERR_FAIL = 1,
4172 #[doc = "FailErrno: Command failed, Err number sent back in PayloadHeader.data[1]. \t\tThis is a file-system error number understood by the server operating system."]
4173 MAV_FTP_ERR_FAILERRNO = 2,
4174 #[doc = "InvalidDataSize: Payload size is invalid"]
4175 MAV_FTP_ERR_INVALIDDATASIZE = 3,
4176 #[doc = "InvalidSession: Session is not currently open"]
4177 MAV_FTP_ERR_INVALIDSESSION = 4,
4178 #[doc = "NoSessionsAvailable: All available sessions are already in use"]
4179 MAV_FTP_ERR_NOSESSIONSAVAILABLE = 5,
4180 #[doc = "EOF: Offset past end of file for ListDirectory and ReadFile commands"]
4181 MAV_FTP_ERR_EOF = 6,
4182 #[doc = "UnknownCommand: Unknown command / opcode"]
4183 MAV_FTP_ERR_UNKNOWNCOMMAND = 7,
4184 #[doc = "FileExists: File/directory already exists"]
4185 MAV_FTP_ERR_FILEEXISTS = 8,
4186 #[doc = "FileProtected: File/directory is write protected"]
4187 MAV_FTP_ERR_FILEPROTECTED = 9,
4188 #[doc = "FileNotFound: File/directory not found"]
4189 MAV_FTP_ERR_FILENOTFOUND = 10,
4190}
4191impl MavFtpErr {
4192 pub const DEFAULT: Self = Self::MAV_FTP_ERR_NONE;
4193}
4194impl Default for MavFtpErr {
4195 fn default() -> Self {
4196 Self::DEFAULT
4197 }
4198}
4199#[cfg_attr(feature = "ts", derive(TS))]
4200#[cfg_attr(feature = "ts", ts(export))]
4201#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4202#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4203#[cfg_attr(feature = "serde", serde(tag = "type"))]
4204#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4205#[repr(u32)]
4206#[doc = "MAV FTP opcodes: <https://mavlink.io/en/services/ftp.html>"]
4207pub enum MavFtpOpcode {
4208 #[doc = "None. Ignored, always ACKed"]
4209 MAV_FTP_OPCODE_NONE = 0,
4210 #[doc = "TerminateSession: Terminates open Read session"]
4211 MAV_FTP_OPCODE_TERMINATESESSION = 1,
4212 #[doc = "ResetSessions: Terminates all open read sessions"]
4213 MAV_FTP_OPCODE_RESETSESSION = 2,
4214 #[doc = "ListDirectory. List files and directories in path from offset"]
4215 MAV_FTP_OPCODE_LISTDIRECTORY = 3,
4216 #[doc = "OpenFileRO: Opens file at path for reading, returns session"]
4217 MAV_FTP_OPCODE_OPENFILERO = 4,
4218 #[doc = "ReadFile: Reads size bytes from offset in session"]
4219 MAV_FTP_OPCODE_READFILE = 5,
4220 #[doc = "CreateFile: Creates file at path for writing, returns session"]
4221 MAV_FTP_OPCODE_CREATEFILE = 6,
4222 #[doc = "WriteFile: Writes size bytes to offset in session"]
4223 MAV_FTP_OPCODE_WRITEFILE = 7,
4224 #[doc = "RemoveFile: Remove file at path"]
4225 MAV_FTP_OPCODE_REMOVEFILE = 8,
4226 #[doc = "CreateDirectory: Creates directory at path"]
4227 MAV_FTP_OPCODE_CREATEDIRECTORY = 9,
4228 #[doc = "RemoveDirectory: Removes directory at path. The directory must be empty."]
4229 MAV_FTP_OPCODE_REMOVEDIRECTORY = 10,
4230 #[doc = "OpenFileWO: Opens file at path for writing, returns session"]
4231 MAV_FTP_OPCODE_OPENFILEWO = 11,
4232 #[doc = "TruncateFile: Truncate file at path to offset length"]
4233 MAV_FTP_OPCODE_TRUNCATEFILE = 12,
4234 #[doc = "Rename: Rename path1 to path2"]
4235 MAV_FTP_OPCODE_RENAME = 13,
4236 #[doc = "CalcFileCRC32: Calculate CRC32 for file at path"]
4237 MAV_FTP_OPCODE_CALCFILECRC = 14,
4238 #[doc = "BurstReadFile: Burst download session file"]
4239 MAV_FTP_OPCODE_BURSTREADFILE = 15,
4240 #[doc = "ACK: ACK response"]
4241 MAV_FTP_OPCODE_ACK = 128,
4242 #[doc = "NAK: NAK response"]
4243 MAV_FTP_OPCODE_NAK = 129,
4244}
4245impl MavFtpOpcode {
4246 pub const DEFAULT: Self = Self::MAV_FTP_OPCODE_NONE;
4247}
4248impl Default for MavFtpOpcode {
4249 fn default() -> Self {
4250 Self::DEFAULT
4251 }
4252}
4253#[cfg_attr(feature = "ts", derive(TS))]
4254#[cfg_attr(feature = "ts", ts(export))]
4255#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4256#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4257#[cfg_attr(feature = "serde", serde(tag = "type"))]
4258#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4259#[repr(u32)]
4260#[doc = "Fuel types for use in FUEL_TYPE. Fuel types specify the units for the maximum, available and consumed fuel, and for the flow rates."]
4261pub enum MavFuelType {
4262 #[doc = "Not specified. Fuel levels are normalized (i.e. maximum is 1, and other levels are relative to 1)."]
4263 MAV_FUEL_TYPE_UNKNOWN = 0,
4264 #[doc = "A generic liquid fuel. Fuel levels are in millilitres (ml). Fuel rates are in millilitres/second."]
4265 MAV_FUEL_TYPE_LIQUID = 1,
4266 #[doc = "A gas tank. Fuel levels are in kilo-Pascal (kPa), and flow rates are in milliliters per second (ml/s)."]
4267 MAV_FUEL_TYPE_GAS = 2,
4268}
4269impl MavFuelType {
4270 pub const DEFAULT: Self = Self::MAV_FUEL_TYPE_UNKNOWN;
4271}
4272impl Default for MavFuelType {
4273 fn default() -> Self {
4274 Self::DEFAULT
4275 }
4276}
4277bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags to report status/failure cases for a power generator (used in GENERATOR_STATUS). Note that FAULTS are conditions that cause the generator to fail. Warnings are conditions that require attention before the next use (they indicate the system is not operating properly)."] pub struct MavGeneratorStatusFlag : u64 { # [doc = "Generator is off."] const MAV_GENERATOR_STATUS_FLAG_OFF = 1 ; # [doc = "Generator is ready to start generating power."] const MAV_GENERATOR_STATUS_FLAG_READY = 2 ; # [doc = "Generator is generating power."] const MAV_GENERATOR_STATUS_FLAG_GENERATING = 4 ; # [doc = "Generator is charging the batteries (generating enough power to charge and provide the load)."] const MAV_GENERATOR_STATUS_FLAG_CHARGING = 8 ; # [doc = "Generator is operating at a reduced maximum power."] const MAV_GENERATOR_STATUS_FLAG_REDUCED_POWER = 16 ; # [doc = "Generator is providing the maximum output."] const MAV_GENERATOR_STATUS_FLAG_MAXPOWER = 32 ; # [doc = "Generator is near the maximum operating temperature, cooling is insufficient."] const MAV_GENERATOR_STATUS_FLAG_OVERTEMP_WARNING = 64 ; # [doc = "Generator hit the maximum operating temperature and shutdown."] const MAV_GENERATOR_STATUS_FLAG_OVERTEMP_FAULT = 128 ; # [doc = "Power electronics are near the maximum operating temperature, cooling is insufficient."] const MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_WARNING = 256 ; # [doc = "Power electronics hit the maximum operating temperature and shutdown."] const MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_FAULT = 512 ; # [doc = "Power electronics experienced a fault and shutdown."] const MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_FAULT = 1024 ; # [doc = "The power source supplying the generator failed e.g. mechanical generator stopped, tether is no longer providing power, solar cell is in shade, hydrogen reaction no longer happening."] const MAV_GENERATOR_STATUS_FLAG_POWERSOURCE_FAULT = 2048 ; # [doc = "Generator controller having communication problems."] const MAV_GENERATOR_STATUS_FLAG_COMMUNICATION_WARNING = 4096 ; # [doc = "Power electronic or generator cooling system error."] const MAV_GENERATOR_STATUS_FLAG_COOLING_WARNING = 8192 ; # [doc = "Generator controller power rail experienced a fault."] const MAV_GENERATOR_STATUS_FLAG_POWER_RAIL_FAULT = 16384 ; # [doc = "Generator controller exceeded the overcurrent threshold and shutdown to prevent damage."] const MAV_GENERATOR_STATUS_FLAG_OVERCURRENT_FAULT = 32768 ; # [doc = "Generator controller detected a high current going into the batteries and shutdown to prevent battery damage."] const MAV_GENERATOR_STATUS_FLAG_BATTERY_OVERCHARGE_CURRENT_FAULT = 65536 ; # [doc = "Generator controller exceeded it's overvoltage threshold and shutdown to prevent it exceeding the voltage rating."] const MAV_GENERATOR_STATUS_FLAG_OVERVOLTAGE_FAULT = 131072 ; # [doc = "Batteries are under voltage (generator will not start)."] const MAV_GENERATOR_STATUS_FLAG_BATTERY_UNDERVOLT_FAULT = 262144 ; # [doc = "Generator start is inhibited by e.g. a safety switch."] const MAV_GENERATOR_STATUS_FLAG_START_INHIBITED = 524288 ; # [doc = "Generator requires maintenance."] const MAV_GENERATOR_STATUS_FLAG_MAINTENANCE_REQUIRED = 1048576 ; # [doc = "Generator is not ready to generate yet."] const MAV_GENERATOR_STATUS_FLAG_WARMING_UP = 2097152 ; # [doc = "Generator is idle."] const MAV_GENERATOR_STATUS_FLAG_IDLE = 4194304 ; } }
4278impl MavGeneratorStatusFlag {
4279 pub const DEFAULT: Self = Self::MAV_GENERATOR_STATUS_FLAG_OFF;
4280}
4281impl Default for MavGeneratorStatusFlag {
4282 fn default() -> Self {
4283 Self::DEFAULT
4284 }
4285}
4286#[cfg_attr(feature = "ts", derive(TS))]
4287#[cfg_attr(feature = "ts", ts(export))]
4288#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4289#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4290#[cfg_attr(feature = "serde", serde(tag = "type"))]
4291#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4292#[repr(u32)]
4293#[doc = "Actions that may be specified in MAV_CMD_OVERRIDE_GOTO to override mission execution."]
4294pub enum MavGoto {
4295 #[doc = "Hold at the current position."]
4296 MAV_GOTO_DO_HOLD = 0,
4297 #[doc = "Continue with the next item in mission execution."]
4298 MAV_GOTO_DO_CONTINUE = 1,
4299 #[doc = "Hold at the current position of the system"]
4300 MAV_GOTO_HOLD_AT_CURRENT_POSITION = 2,
4301 #[doc = "Hold at the position specified in the parameters of the DO_HOLD action"]
4302 MAV_GOTO_HOLD_AT_SPECIFIED_POSITION = 3,
4303}
4304impl MavGoto {
4305 pub const DEFAULT: Self = Self::MAV_GOTO_DO_HOLD;
4306}
4307impl Default for MavGoto {
4308 fn default() -> Self {
4309 Self::DEFAULT
4310 }
4311}
4312#[cfg_attr(feature = "ts", derive(TS))]
4313#[cfg_attr(feature = "ts", ts(export))]
4314#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4315#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4316#[cfg_attr(feature = "serde", serde(tag = "type"))]
4317#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4318#[repr(u32)]
4319#[doc = "Enumeration of landed detector states"]
4320pub enum MavLandedState {
4321 #[doc = "MAV landed state is unknown"]
4322 MAV_LANDED_STATE_UNDEFINED = 0,
4323 #[doc = "MAV is landed (on ground)"]
4324 MAV_LANDED_STATE_ON_GROUND = 1,
4325 #[doc = "MAV is in air"]
4326 MAV_LANDED_STATE_IN_AIR = 2,
4327 #[doc = "MAV currently taking off"]
4328 MAV_LANDED_STATE_TAKEOFF = 3,
4329 #[doc = "MAV currently landing"]
4330 MAV_LANDED_STATE_LANDING = 4,
4331}
4332impl MavLandedState {
4333 pub const DEFAULT: Self = Self::MAV_LANDED_STATE_UNDEFINED;
4334}
4335impl Default for MavLandedState {
4336 fn default() -> Self {
4337 Self::DEFAULT
4338 }
4339}
4340#[cfg_attr(feature = "ts", derive(TS))]
4341#[cfg_attr(feature = "ts", ts(export))]
4342#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4343#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4344#[cfg_attr(feature = "serde", serde(tag = "type"))]
4345#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4346#[repr(u32)]
4347#[doc = "Result of mission operation (in a MISSION_ACK message)."]
4348pub enum MavMissionResult {
4349 #[doc = "mission accepted OK"]
4350 MAV_MISSION_ACCEPTED = 0,
4351 #[doc = "Generic error / not accepting mission commands at all right now."]
4352 MAV_MISSION_ERROR = 1,
4353 #[doc = "Coordinate frame is not supported."]
4354 MAV_MISSION_UNSUPPORTED_FRAME = 2,
4355 #[doc = "Command is not supported."]
4356 MAV_MISSION_UNSUPPORTED = 3,
4357 #[doc = "Mission items exceed storage space."]
4358 MAV_MISSION_NO_SPACE = 4,
4359 #[doc = "One of the parameters has an invalid value."]
4360 MAV_MISSION_INVALID = 5,
4361 #[doc = "param1 has an invalid value."]
4362 MAV_MISSION_INVALID_PARAM1 = 6,
4363 #[doc = "param2 has an invalid value."]
4364 MAV_MISSION_INVALID_PARAM2 = 7,
4365 #[doc = "param3 has an invalid value."]
4366 MAV_MISSION_INVALID_PARAM3 = 8,
4367 #[doc = "param4 has an invalid value."]
4368 MAV_MISSION_INVALID_PARAM4 = 9,
4369 #[doc = "x / param5 has an invalid value."]
4370 MAV_MISSION_INVALID_PARAM5_X = 10,
4371 #[doc = "y / param6 has an invalid value."]
4372 MAV_MISSION_INVALID_PARAM6_Y = 11,
4373 #[doc = "z / param7 has an invalid value."]
4374 MAV_MISSION_INVALID_PARAM7 = 12,
4375 #[doc = "Mission item received out of sequence"]
4376 MAV_MISSION_INVALID_SEQUENCE = 13,
4377 #[doc = "Not accepting any mission commands from this communication partner."]
4378 MAV_MISSION_DENIED = 14,
4379 #[doc = "Current mission operation cancelled (e.g. mission upload, mission download)."]
4380 MAV_MISSION_OPERATION_CANCELLED = 15,
4381}
4382impl MavMissionResult {
4383 pub const DEFAULT: Self = Self::MAV_MISSION_ACCEPTED;
4384}
4385impl Default for MavMissionResult {
4386 fn default() -> Self {
4387 Self::DEFAULT
4388 }
4389}
4390#[cfg_attr(feature = "ts", derive(TS))]
4391#[cfg_attr(feature = "ts", ts(export))]
4392#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4393#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4394#[cfg_attr(feature = "serde", serde(tag = "type"))]
4395#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4396#[repr(u32)]
4397#[doc = "Type of mission items being requested/sent in mission protocol."]
4398pub enum MavMissionType {
4399 #[doc = "Items are mission commands for main mission."]
4400 MAV_MISSION_TYPE_MISSION = 0,
4401 #[doc = "Specifies GeoFence area(s). Items are MAV_CMD_NAV_FENCE_ GeoFence items."]
4402 MAV_MISSION_TYPE_FENCE = 1,
4403 #[doc = "Specifies the rally points for the vehicle. Rally points are alternative RTL points. Items are MAV_CMD_NAV_RALLY_POINT rally point items."]
4404 MAV_MISSION_TYPE_RALLY = 2,
4405 #[doc = "Only used in MISSION_CLEAR_ALL to clear all mission types."]
4406 MAV_MISSION_TYPE_ALL = 255,
4407}
4408impl MavMissionType {
4409 pub const DEFAULT: Self = Self::MAV_MISSION_TYPE_MISSION;
4410}
4411impl Default for MavMissionType {
4412 fn default() -> Self {
4413 Self::DEFAULT
4414 }
4415}
4416#[cfg_attr(feature = "ts", derive(TS))]
4417#[cfg_attr(feature = "ts", ts(export))]
4418#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4419#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4420#[cfg_attr(feature = "serde", serde(tag = "type"))]
4421#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4422#[repr(u32)]
4423#[doc = "These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override."]
4424pub enum MavMode {
4425 #[doc = "System is not ready to fly, booting, calibrating, etc. No flag is set."]
4426 MAV_MODE_PREFLIGHT = 0,
4427 #[doc = "System is allowed to be active, under assisted RC control."]
4428 MAV_MODE_STABILIZE_DISARMED = 80,
4429 #[doc = "System is allowed to be active, under assisted RC control."]
4430 MAV_MODE_STABILIZE_ARMED = 208,
4431 #[doc = "System is allowed to be active, under manual (RC) control, no stabilization"]
4432 MAV_MODE_MANUAL_DISARMED = 64,
4433 #[doc = "System is allowed to be active, under manual (RC) control, no stabilization"]
4434 MAV_MODE_MANUAL_ARMED = 192,
4435 #[doc = "System is allowed to be active, under autonomous control, manual setpoint"]
4436 MAV_MODE_GUIDED_DISARMED = 88,
4437 #[doc = "System is allowed to be active, under autonomous control, manual setpoint"]
4438 MAV_MODE_GUIDED_ARMED = 216,
4439 #[doc = "System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints)"]
4440 MAV_MODE_AUTO_DISARMED = 92,
4441 #[doc = "System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints)"]
4442 MAV_MODE_AUTO_ARMED = 220,
4443 #[doc = "UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only."]
4444 MAV_MODE_TEST_DISARMED = 66,
4445 #[doc = "UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only."]
4446 MAV_MODE_TEST_ARMED = 194,
4447}
4448impl MavMode {
4449 pub const DEFAULT: Self = Self::MAV_MODE_PREFLIGHT;
4450}
4451impl Default for MavMode {
4452 fn default() -> Self {
4453 Self::DEFAULT
4454 }
4455}
4456bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These flags encode the MAV mode."] pub struct MavModeFlag : u8 { # [doc = "0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. Additional note: this flag is to be ignore when sent in the command MAV_CMD_DO_SET_MODE and MAV_CMD_COMPONENT_ARM_DISARM shall be used instead. The flag can still be used to report the armed state."] const MAV_MODE_FLAG_SAFETY_ARMED = 128 ; # [doc = "0b01000000 remote control input is enabled."] const MAV_MODE_FLAG_MANUAL_INPUT_ENABLED = 64 ; # [doc = "0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational."] const MAV_MODE_FLAG_HIL_ENABLED = 32 ; # [doc = "0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around."] const MAV_MODE_FLAG_STABILIZE_ENABLED = 16 ; # [doc = "0b00001000 guided mode enabled, system flies waypoints / mission items."] const MAV_MODE_FLAG_GUIDED_ENABLED = 8 ; # [doc = "0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation."] const MAV_MODE_FLAG_AUTO_ENABLED = 4 ; # [doc = "0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations."] const MAV_MODE_FLAG_TEST_ENABLED = 2 ; # [doc = "0b00000001 Reserved for future use."] const MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = 1 ; } }
4457impl MavModeFlag {
4458 pub const DEFAULT: Self = Self::MAV_MODE_FLAG_SAFETY_ARMED;
4459}
4460impl Default for MavModeFlag {
4461 fn default() -> Self {
4462 Self::DEFAULT
4463 }
4464}
4465#[cfg_attr(feature = "ts", derive(TS))]
4466#[cfg_attr(feature = "ts", ts(export))]
4467#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4468#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4469#[cfg_attr(feature = "serde", serde(tag = "type"))]
4470#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4471#[repr(u32)]
4472#[doc = "These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not."]
4473pub enum MavModeFlagDecodePosition {
4474 #[doc = "First bit: 10000000"]
4475 MAV_MODE_FLAG_DECODE_POSITION_SAFETY = 128,
4476 #[doc = "Second bit: 01000000"]
4477 MAV_MODE_FLAG_DECODE_POSITION_MANUAL = 64,
4478 #[doc = "Third bit: 00100000"]
4479 MAV_MODE_FLAG_DECODE_POSITION_HIL = 32,
4480 #[doc = "Fourth bit: 00010000"]
4481 MAV_MODE_FLAG_DECODE_POSITION_STABILIZE = 16,
4482 #[doc = "Fifth bit: 00001000"]
4483 MAV_MODE_FLAG_DECODE_POSITION_GUIDED = 8,
4484 #[doc = "Sixth bit: 00000100"]
4485 MAV_MODE_FLAG_DECODE_POSITION_AUTO = 4,
4486 #[doc = "Seventh bit: 00000010"]
4487 MAV_MODE_FLAG_DECODE_POSITION_TEST = 2,
4488 #[doc = "Eighth bit: 00000001"]
4489 MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE = 1,
4490}
4491impl MavModeFlagDecodePosition {
4492 pub const DEFAULT: Self = Self::MAV_MODE_FLAG_DECODE_POSITION_SAFETY;
4493}
4494impl Default for MavModeFlagDecodePosition {
4495 fn default() -> Self {
4496 Self::DEFAULT
4497 }
4498}
4499bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Mode properties."] pub struct MavModeProperty : u32 { # [doc = "If set, this mode is an advanced mode. For example a rate-controlled manual mode might be advanced, whereas a position-controlled manual mode is not. A GCS can optionally use this flag to configure the UI for its intended users."] const MAV_MODE_PROPERTY_ADVANCED = 1 ; # [doc = "If set, this mode should not be added to the list of selectable modes. The mode might still be selected by the FC directly (for example as part of a failsafe)."] const MAV_MODE_PROPERTY_NOT_USER_SELECTABLE = 2 ; # [doc = "If set, this mode is automatically controlled (it may use but does not require a manual controller). If unset the mode is a assumed to require user input (be a manual mode)."] const MAV_MODE_PROPERTY_AUTO_MODE = 4 ; } }
4500impl MavModeProperty {
4501 pub const DEFAULT: Self = Self::MAV_MODE_PROPERTY_ADVANCED;
4502}
4503impl Default for MavModeProperty {
4504 fn default() -> Self {
4505 Self::DEFAULT
4506 }
4507}
4508#[cfg_attr(feature = "ts", derive(TS))]
4509#[cfg_attr(feature = "ts", ts(export))]
4510#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4511#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4512#[cfg_attr(feature = "serde", serde(tag = "type"))]
4513#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4514#[repr(u32)]
4515#[deprecated = " See `GIMBAL_MANAGER_FLAGS` (Deprecated since 2020-01)"]
4516#[doc = "Enumeration of possible mount operation modes. This message is used by obsolete/deprecated gimbal messages."]
4517pub enum MavMountMode {
4518 #[doc = "Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization"]
4519 MAV_MOUNT_MODE_RETRACT = 0,
4520 #[doc = "Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory."]
4521 MAV_MOUNT_MODE_NEUTRAL = 1,
4522 #[doc = "Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization"]
4523 MAV_MOUNT_MODE_MAVLINK_TARGETING = 2,
4524 #[doc = "Load neutral position and start RC Roll,Pitch,Yaw control with stabilization"]
4525 MAV_MOUNT_MODE_RC_TARGETING = 3,
4526 #[doc = "Load neutral position and start to point to Lat,Lon,Alt"]
4527 MAV_MOUNT_MODE_GPS_POINT = 4,
4528 #[doc = "Gimbal tracks system with specified system ID"]
4529 MAV_MOUNT_MODE_SYSID_TARGET = 5,
4530 #[doc = "Gimbal tracks home position"]
4531 MAV_MOUNT_MODE_HOME_LOCATION = 6,
4532}
4533impl MavMountMode {
4534 pub const DEFAULT: Self = Self::MAV_MOUNT_MODE_RETRACT;
4535}
4536impl Default for MavMountMode {
4537 fn default() -> Self {
4538 Self::DEFAULT
4539 }
4540}
4541#[cfg_attr(feature = "ts", derive(TS))]
4542#[cfg_attr(feature = "ts", ts(export))]
4543#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4544#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4545#[cfg_attr(feature = "serde", serde(tag = "type"))]
4546#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4547#[repr(u32)]
4548pub enum MavOdidArmStatus {
4549 #[doc = "Passing arming checks."]
4550 MAV_ODID_ARM_STATUS_GOOD_TO_ARM = 0,
4551 #[doc = "Generic arming failure, see error string for details."]
4552 MAV_ODID_ARM_STATUS_PRE_ARM_FAIL_GENERIC = 1,
4553}
4554impl MavOdidArmStatus {
4555 pub const DEFAULT: Self = Self::MAV_ODID_ARM_STATUS_GOOD_TO_ARM;
4556}
4557impl Default for MavOdidArmStatus {
4558 fn default() -> Self {
4559 Self::DEFAULT
4560 }
4561}
4562#[cfg_attr(feature = "ts", derive(TS))]
4563#[cfg_attr(feature = "ts", ts(export))]
4564#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4565#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4566#[cfg_attr(feature = "serde", serde(tag = "type"))]
4567#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4568#[repr(u32)]
4569pub enum MavOdidAuthType {
4570 #[doc = "No authentication type is specified."]
4571 MAV_ODID_AUTH_TYPE_NONE = 0,
4572 #[doc = "Signature for the UAS (Unmanned Aircraft System) ID."]
4573 MAV_ODID_AUTH_TYPE_UAS_ID_SIGNATURE = 1,
4574 #[doc = "Signature for the Operator ID."]
4575 MAV_ODID_AUTH_TYPE_OPERATOR_ID_SIGNATURE = 2,
4576 #[doc = "Signature for the entire message set."]
4577 MAV_ODID_AUTH_TYPE_MESSAGE_SET_SIGNATURE = 3,
4578 #[doc = "Authentication is provided by Network Remote ID."]
4579 MAV_ODID_AUTH_TYPE_NETWORK_REMOTE_ID = 4,
4580 #[doc = "The exact authentication type is indicated by the first byte of authentication_data and these type values are managed by ICAO."]
4581 MAV_ODID_AUTH_TYPE_SPECIFIC_AUTHENTICATION = 5,
4582}
4583impl MavOdidAuthType {
4584 pub const DEFAULT: Self = Self::MAV_ODID_AUTH_TYPE_NONE;
4585}
4586impl Default for MavOdidAuthType {
4587 fn default() -> Self {
4588 Self::DEFAULT
4589 }
4590}
4591#[cfg_attr(feature = "ts", derive(TS))]
4592#[cfg_attr(feature = "ts", ts(export))]
4593#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4594#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4595#[cfg_attr(feature = "serde", serde(tag = "type"))]
4596#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4597#[repr(u32)]
4598pub enum MavOdidCategoryEu {
4599 #[doc = "The category for the UA, according to the EU specification, is undeclared."]
4600 MAV_ODID_CATEGORY_EU_UNDECLARED = 0,
4601 #[doc = "The category for the UA, according to the EU specification, is the Open category."]
4602 MAV_ODID_CATEGORY_EU_OPEN = 1,
4603 #[doc = "The category for the UA, according to the EU specification, is the Specific category."]
4604 MAV_ODID_CATEGORY_EU_SPECIFIC = 2,
4605 #[doc = "The category for the UA, according to the EU specification, is the Certified category."]
4606 MAV_ODID_CATEGORY_EU_CERTIFIED = 3,
4607}
4608impl MavOdidCategoryEu {
4609 pub const DEFAULT: Self = Self::MAV_ODID_CATEGORY_EU_UNDECLARED;
4610}
4611impl Default for MavOdidCategoryEu {
4612 fn default() -> Self {
4613 Self::DEFAULT
4614 }
4615}
4616#[cfg_attr(feature = "ts", derive(TS))]
4617#[cfg_attr(feature = "ts", ts(export))]
4618#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4619#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4620#[cfg_attr(feature = "serde", serde(tag = "type"))]
4621#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4622#[repr(u32)]
4623pub enum MavOdidClassEu {
4624 #[doc = "The class for the UA, according to the EU specification, is undeclared."]
4625 MAV_ODID_CLASS_EU_UNDECLARED = 0,
4626 #[doc = "The class for the UA, according to the EU specification, is Class 0."]
4627 MAV_ODID_CLASS_EU_CLASS_0 = 1,
4628 #[doc = "The class for the UA, according to the EU specification, is Class 1."]
4629 MAV_ODID_CLASS_EU_CLASS_1 = 2,
4630 #[doc = "The class for the UA, according to the EU specification, is Class 2."]
4631 MAV_ODID_CLASS_EU_CLASS_2 = 3,
4632 #[doc = "The class for the UA, according to the EU specification, is Class 3."]
4633 MAV_ODID_CLASS_EU_CLASS_3 = 4,
4634 #[doc = "The class for the UA, according to the EU specification, is Class 4."]
4635 MAV_ODID_CLASS_EU_CLASS_4 = 5,
4636 #[doc = "The class for the UA, according to the EU specification, is Class 5."]
4637 MAV_ODID_CLASS_EU_CLASS_5 = 6,
4638 #[doc = "The class for the UA, according to the EU specification, is Class 6."]
4639 MAV_ODID_CLASS_EU_CLASS_6 = 7,
4640}
4641impl MavOdidClassEu {
4642 pub const DEFAULT: Self = Self::MAV_ODID_CLASS_EU_UNDECLARED;
4643}
4644impl Default for MavOdidClassEu {
4645 fn default() -> Self {
4646 Self::DEFAULT
4647 }
4648}
4649#[cfg_attr(feature = "ts", derive(TS))]
4650#[cfg_attr(feature = "ts", ts(export))]
4651#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4652#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4653#[cfg_attr(feature = "serde", serde(tag = "type"))]
4654#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4655#[repr(u32)]
4656pub enum MavOdidClassificationType {
4657 #[doc = "The classification type for the UA is undeclared."]
4658 MAV_ODID_CLASSIFICATION_TYPE_UNDECLARED = 0,
4659 #[doc = "The classification type for the UA follows EU (European Union) specifications."]
4660 MAV_ODID_CLASSIFICATION_TYPE_EU = 1,
4661}
4662impl MavOdidClassificationType {
4663 pub const DEFAULT: Self = Self::MAV_ODID_CLASSIFICATION_TYPE_UNDECLARED;
4664}
4665impl Default for MavOdidClassificationType {
4666 fn default() -> Self {
4667 Self::DEFAULT
4668 }
4669}
4670#[cfg_attr(feature = "ts", derive(TS))]
4671#[cfg_attr(feature = "ts", ts(export))]
4672#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4673#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4674#[cfg_attr(feature = "serde", serde(tag = "type"))]
4675#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4676#[repr(u32)]
4677pub enum MavOdidDescType {
4678 #[doc = "Optional free-form text description of the purpose of the flight."]
4679 MAV_ODID_DESC_TYPE_TEXT = 0,
4680 #[doc = "Optional additional clarification when status == MAV_ODID_STATUS_EMERGENCY."]
4681 MAV_ODID_DESC_TYPE_EMERGENCY = 1,
4682 #[doc = "Optional additional clarification when status != MAV_ODID_STATUS_EMERGENCY."]
4683 MAV_ODID_DESC_TYPE_EXTENDED_STATUS = 2,
4684}
4685impl MavOdidDescType {
4686 pub const DEFAULT: Self = Self::MAV_ODID_DESC_TYPE_TEXT;
4687}
4688impl Default for MavOdidDescType {
4689 fn default() -> Self {
4690 Self::DEFAULT
4691 }
4692}
4693#[cfg_attr(feature = "ts", derive(TS))]
4694#[cfg_attr(feature = "ts", ts(export))]
4695#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4696#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4697#[cfg_attr(feature = "serde", serde(tag = "type"))]
4698#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4699#[repr(u32)]
4700pub enum MavOdidHeightRef {
4701 #[doc = "The height field is relative to the take-off location."]
4702 MAV_ODID_HEIGHT_REF_OVER_TAKEOFF = 0,
4703 #[doc = "The height field is relative to ground."]
4704 MAV_ODID_HEIGHT_REF_OVER_GROUND = 1,
4705}
4706impl MavOdidHeightRef {
4707 pub const DEFAULT: Self = Self::MAV_ODID_HEIGHT_REF_OVER_TAKEOFF;
4708}
4709impl Default for MavOdidHeightRef {
4710 fn default() -> Self {
4711 Self::DEFAULT
4712 }
4713}
4714#[cfg_attr(feature = "ts", derive(TS))]
4715#[cfg_attr(feature = "ts", ts(export))]
4716#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4717#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4718#[cfg_attr(feature = "serde", serde(tag = "type"))]
4719#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4720#[repr(u32)]
4721pub enum MavOdidHorAcc {
4722 #[doc = "The horizontal accuracy is unknown."]
4723 MAV_ODID_HOR_ACC_UNKNOWN = 0,
4724 #[doc = "The horizontal accuracy is smaller than 10 Nautical Miles. 18.52 km."]
4725 MAV_ODID_HOR_ACC_10NM = 1,
4726 #[doc = "The horizontal accuracy is smaller than 4 Nautical Miles. 7.408 km."]
4727 MAV_ODID_HOR_ACC_4NM = 2,
4728 #[doc = "The horizontal accuracy is smaller than 2 Nautical Miles. 3.704 km."]
4729 MAV_ODID_HOR_ACC_2NM = 3,
4730 #[doc = "The horizontal accuracy is smaller than 1 Nautical Miles. 1.852 km."]
4731 MAV_ODID_HOR_ACC_1NM = 4,
4732 #[doc = "The horizontal accuracy is smaller than 0.5 Nautical Miles. 926 m."]
4733 MAV_ODID_HOR_ACC_0_5NM = 5,
4734 #[doc = "The horizontal accuracy is smaller than 0.3 Nautical Miles. 555.6 m."]
4735 MAV_ODID_HOR_ACC_0_3NM = 6,
4736 #[doc = "The horizontal accuracy is smaller than 0.1 Nautical Miles. 185.2 m."]
4737 MAV_ODID_HOR_ACC_0_1NM = 7,
4738 #[doc = "The horizontal accuracy is smaller than 0.05 Nautical Miles. 92.6 m."]
4739 MAV_ODID_HOR_ACC_0_05NM = 8,
4740 #[doc = "The horizontal accuracy is smaller than 30 meter."]
4741 MAV_ODID_HOR_ACC_30_METER = 9,
4742 #[doc = "The horizontal accuracy is smaller than 10 meter."]
4743 MAV_ODID_HOR_ACC_10_METER = 10,
4744 #[doc = "The horizontal accuracy is smaller than 3 meter."]
4745 MAV_ODID_HOR_ACC_3_METER = 11,
4746 #[doc = "The horizontal accuracy is smaller than 1 meter."]
4747 MAV_ODID_HOR_ACC_1_METER = 12,
4748}
4749impl MavOdidHorAcc {
4750 pub const DEFAULT: Self = Self::MAV_ODID_HOR_ACC_UNKNOWN;
4751}
4752impl Default for MavOdidHorAcc {
4753 fn default() -> Self {
4754 Self::DEFAULT
4755 }
4756}
4757#[cfg_attr(feature = "ts", derive(TS))]
4758#[cfg_attr(feature = "ts", ts(export))]
4759#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4760#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4761#[cfg_attr(feature = "serde", serde(tag = "type"))]
4762#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4763#[repr(u32)]
4764pub enum MavOdidIdType {
4765 #[doc = "No type defined."]
4766 MAV_ODID_ID_TYPE_NONE = 0,
4767 #[doc = "Manufacturer Serial Number (ANSI/CTA-2063 format)."]
4768 MAV_ODID_ID_TYPE_SERIAL_NUMBER = 1,
4769 #[doc = "CAA (Civil Aviation Authority) registered ID. Format: [ICAO Country Code].[CAA Assigned ID]."]
4770 MAV_ODID_ID_TYPE_CAA_REGISTRATION_ID = 2,
4771 #[doc = "UTM (Unmanned Traffic Management) assigned UUID (RFC4122)."]
4772 MAV_ODID_ID_TYPE_UTM_ASSIGNED_UUID = 3,
4773 #[doc = "A 20 byte ID for a specific flight/session. The exact ID type is indicated by the first byte of uas_id and these type values are managed by ICAO."]
4774 MAV_ODID_ID_TYPE_SPECIFIC_SESSION_ID = 4,
4775}
4776impl MavOdidIdType {
4777 pub const DEFAULT: Self = Self::MAV_ODID_ID_TYPE_NONE;
4778}
4779impl Default for MavOdidIdType {
4780 fn default() -> Self {
4781 Self::DEFAULT
4782 }
4783}
4784#[cfg_attr(feature = "ts", derive(TS))]
4785#[cfg_attr(feature = "ts", ts(export))]
4786#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4787#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4788#[cfg_attr(feature = "serde", serde(tag = "type"))]
4789#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4790#[repr(u32)]
4791pub enum MavOdidOperatorIdType {
4792 #[doc = "CAA (Civil Aviation Authority) registered operator ID."]
4793 MAV_ODID_OPERATOR_ID_TYPE_CAA = 0,
4794}
4795impl MavOdidOperatorIdType {
4796 pub const DEFAULT: Self = Self::MAV_ODID_OPERATOR_ID_TYPE_CAA;
4797}
4798impl Default for MavOdidOperatorIdType {
4799 fn default() -> Self {
4800 Self::DEFAULT
4801 }
4802}
4803#[cfg_attr(feature = "ts", derive(TS))]
4804#[cfg_attr(feature = "ts", ts(export))]
4805#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4806#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4807#[cfg_attr(feature = "serde", serde(tag = "type"))]
4808#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4809#[repr(u32)]
4810pub enum MavOdidOperatorLocationType {
4811 #[doc = "The location/altitude of the operator is the same as the take-off location."]
4812 MAV_ODID_OPERATOR_LOCATION_TYPE_TAKEOFF = 0,
4813 #[doc = "The location/altitude of the operator is dynamic. E.g. based on live GNSS data."]
4814 MAV_ODID_OPERATOR_LOCATION_TYPE_LIVE_GNSS = 1,
4815 #[doc = "The location/altitude of the operator are fixed values."]
4816 MAV_ODID_OPERATOR_LOCATION_TYPE_FIXED = 2,
4817}
4818impl MavOdidOperatorLocationType {
4819 pub const DEFAULT: Self = Self::MAV_ODID_OPERATOR_LOCATION_TYPE_TAKEOFF;
4820}
4821impl Default for MavOdidOperatorLocationType {
4822 fn default() -> Self {
4823 Self::DEFAULT
4824 }
4825}
4826#[cfg_attr(feature = "ts", derive(TS))]
4827#[cfg_attr(feature = "ts", ts(export))]
4828#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4829#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4830#[cfg_attr(feature = "serde", serde(tag = "type"))]
4831#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4832#[repr(u32)]
4833pub enum MavOdidSpeedAcc {
4834 #[doc = "The speed accuracy is unknown."]
4835 MAV_ODID_SPEED_ACC_UNKNOWN = 0,
4836 #[doc = "The speed accuracy is smaller than 10 meters per second."]
4837 MAV_ODID_SPEED_ACC_10_METERS_PER_SECOND = 1,
4838 #[doc = "The speed accuracy is smaller than 3 meters per second."]
4839 MAV_ODID_SPEED_ACC_3_METERS_PER_SECOND = 2,
4840 #[doc = "The speed accuracy is smaller than 1 meters per second."]
4841 MAV_ODID_SPEED_ACC_1_METERS_PER_SECOND = 3,
4842 #[doc = "The speed accuracy is smaller than 0.3 meters per second."]
4843 MAV_ODID_SPEED_ACC_0_3_METERS_PER_SECOND = 4,
4844}
4845impl MavOdidSpeedAcc {
4846 pub const DEFAULT: Self = Self::MAV_ODID_SPEED_ACC_UNKNOWN;
4847}
4848impl Default for MavOdidSpeedAcc {
4849 fn default() -> Self {
4850 Self::DEFAULT
4851 }
4852}
4853#[cfg_attr(feature = "ts", derive(TS))]
4854#[cfg_attr(feature = "ts", ts(export))]
4855#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4856#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4857#[cfg_attr(feature = "serde", serde(tag = "type"))]
4858#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4859#[repr(u32)]
4860pub enum MavOdidStatus {
4861 #[doc = "The status of the (UA) Unmanned Aircraft is undefined."]
4862 MAV_ODID_STATUS_UNDECLARED = 0,
4863 #[doc = "The UA is on the ground."]
4864 MAV_ODID_STATUS_GROUND = 1,
4865 #[doc = "The UA is in the air."]
4866 MAV_ODID_STATUS_AIRBORNE = 2,
4867 #[doc = "The UA is having an emergency."]
4868 MAV_ODID_STATUS_EMERGENCY = 3,
4869 #[doc = "The remote ID system is failing or unreliable in some way."]
4870 MAV_ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE = 4,
4871}
4872impl MavOdidStatus {
4873 pub const DEFAULT: Self = Self::MAV_ODID_STATUS_UNDECLARED;
4874}
4875impl Default for MavOdidStatus {
4876 fn default() -> Self {
4877 Self::DEFAULT
4878 }
4879}
4880#[cfg_attr(feature = "ts", derive(TS))]
4881#[cfg_attr(feature = "ts", ts(export))]
4882#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4883#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4884#[cfg_attr(feature = "serde", serde(tag = "type"))]
4885#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4886#[repr(u32)]
4887pub enum MavOdidTimeAcc {
4888 #[doc = "The timestamp accuracy is unknown."]
4889 MAV_ODID_TIME_ACC_UNKNOWN = 0,
4890 #[doc = "The timestamp accuracy is smaller than or equal to 0.1 second."]
4891 MAV_ODID_TIME_ACC_0_1_SECOND = 1,
4892 #[doc = "The timestamp accuracy is smaller than or equal to 0.2 second."]
4893 MAV_ODID_TIME_ACC_0_2_SECOND = 2,
4894 #[doc = "The timestamp accuracy is smaller than or equal to 0.3 second."]
4895 MAV_ODID_TIME_ACC_0_3_SECOND = 3,
4896 #[doc = "The timestamp accuracy is smaller than or equal to 0.4 second."]
4897 MAV_ODID_TIME_ACC_0_4_SECOND = 4,
4898 #[doc = "The timestamp accuracy is smaller than or equal to 0.5 second."]
4899 MAV_ODID_TIME_ACC_0_5_SECOND = 5,
4900 #[doc = "The timestamp accuracy is smaller than or equal to 0.6 second."]
4901 MAV_ODID_TIME_ACC_0_6_SECOND = 6,
4902 #[doc = "The timestamp accuracy is smaller than or equal to 0.7 second."]
4903 MAV_ODID_TIME_ACC_0_7_SECOND = 7,
4904 #[doc = "The timestamp accuracy is smaller than or equal to 0.8 second."]
4905 MAV_ODID_TIME_ACC_0_8_SECOND = 8,
4906 #[doc = "The timestamp accuracy is smaller than or equal to 0.9 second."]
4907 MAV_ODID_TIME_ACC_0_9_SECOND = 9,
4908 #[doc = "The timestamp accuracy is smaller than or equal to 1.0 second."]
4909 MAV_ODID_TIME_ACC_1_0_SECOND = 10,
4910 #[doc = "The timestamp accuracy is smaller than or equal to 1.1 second."]
4911 MAV_ODID_TIME_ACC_1_1_SECOND = 11,
4912 #[doc = "The timestamp accuracy is smaller than or equal to 1.2 second."]
4913 MAV_ODID_TIME_ACC_1_2_SECOND = 12,
4914 #[doc = "The timestamp accuracy is smaller than or equal to 1.3 second."]
4915 MAV_ODID_TIME_ACC_1_3_SECOND = 13,
4916 #[doc = "The timestamp accuracy is smaller than or equal to 1.4 second."]
4917 MAV_ODID_TIME_ACC_1_4_SECOND = 14,
4918 #[doc = "The timestamp accuracy is smaller than or equal to 1.5 second."]
4919 MAV_ODID_TIME_ACC_1_5_SECOND = 15,
4920}
4921impl MavOdidTimeAcc {
4922 pub const DEFAULT: Self = Self::MAV_ODID_TIME_ACC_UNKNOWN;
4923}
4924impl Default for MavOdidTimeAcc {
4925 fn default() -> Self {
4926 Self::DEFAULT
4927 }
4928}
4929#[cfg_attr(feature = "ts", derive(TS))]
4930#[cfg_attr(feature = "ts", ts(export))]
4931#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4932#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4933#[cfg_attr(feature = "serde", serde(tag = "type"))]
4934#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4935#[repr(u32)]
4936pub enum MavOdidUaType {
4937 #[doc = "No UA (Unmanned Aircraft) type defined."]
4938 MAV_ODID_UA_TYPE_NONE = 0,
4939 #[doc = "Aeroplane/Airplane. Fixed wing."]
4940 MAV_ODID_UA_TYPE_AEROPLANE = 1,
4941 #[doc = "Helicopter or multirotor."]
4942 MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR = 2,
4943 #[doc = "Gyroplane."]
4944 MAV_ODID_UA_TYPE_GYROPLANE = 3,
4945 #[doc = "VTOL (Vertical Take-Off and Landing). Fixed wing aircraft that can take off vertically."]
4946 MAV_ODID_UA_TYPE_HYBRID_LIFT = 4,
4947 #[doc = "Ornithopter."]
4948 MAV_ODID_UA_TYPE_ORNITHOPTER = 5,
4949 #[doc = "Glider."]
4950 MAV_ODID_UA_TYPE_GLIDER = 6,
4951 #[doc = "Kite."]
4952 MAV_ODID_UA_TYPE_KITE = 7,
4953 #[doc = "Free Balloon."]
4954 MAV_ODID_UA_TYPE_FREE_BALLOON = 8,
4955 #[doc = "Captive Balloon."]
4956 MAV_ODID_UA_TYPE_CAPTIVE_BALLOON = 9,
4957 #[doc = "Airship. E.g. a blimp."]
4958 MAV_ODID_UA_TYPE_AIRSHIP = 10,
4959 #[doc = "Free Fall/Parachute (unpowered)."]
4960 MAV_ODID_UA_TYPE_FREE_FALL_PARACHUTE = 11,
4961 #[doc = "Rocket."]
4962 MAV_ODID_UA_TYPE_ROCKET = 12,
4963 #[doc = "Tethered powered aircraft."]
4964 MAV_ODID_UA_TYPE_TETHERED_POWERED_AIRCRAFT = 13,
4965 #[doc = "Ground Obstacle."]
4966 MAV_ODID_UA_TYPE_GROUND_OBSTACLE = 14,
4967 #[doc = "Other type of aircraft not listed earlier."]
4968 MAV_ODID_UA_TYPE_OTHER = 15,
4969}
4970impl MavOdidUaType {
4971 pub const DEFAULT: Self = Self::MAV_ODID_UA_TYPE_NONE;
4972}
4973impl Default for MavOdidUaType {
4974 fn default() -> Self {
4975 Self::DEFAULT
4976 }
4977}
4978#[cfg_attr(feature = "ts", derive(TS))]
4979#[cfg_attr(feature = "ts", ts(export))]
4980#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4981#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4982#[cfg_attr(feature = "serde", serde(tag = "type"))]
4983#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4984#[repr(u32)]
4985pub enum MavOdidVerAcc {
4986 #[doc = "The vertical accuracy is unknown."]
4987 MAV_ODID_VER_ACC_UNKNOWN = 0,
4988 #[doc = "The vertical accuracy is smaller than 150 meter."]
4989 MAV_ODID_VER_ACC_150_METER = 1,
4990 #[doc = "The vertical accuracy is smaller than 45 meter."]
4991 MAV_ODID_VER_ACC_45_METER = 2,
4992 #[doc = "The vertical accuracy is smaller than 25 meter."]
4993 MAV_ODID_VER_ACC_25_METER = 3,
4994 #[doc = "The vertical accuracy is smaller than 10 meter."]
4995 MAV_ODID_VER_ACC_10_METER = 4,
4996 #[doc = "The vertical accuracy is smaller than 3 meter."]
4997 MAV_ODID_VER_ACC_3_METER = 5,
4998 #[doc = "The vertical accuracy is smaller than 1 meter."]
4999 MAV_ODID_VER_ACC_1_METER = 6,
5000}
5001impl MavOdidVerAcc {
5002 pub const DEFAULT: Self = Self::MAV_ODID_VER_ACC_UNKNOWN;
5003}
5004impl Default for MavOdidVerAcc {
5005 fn default() -> Self {
5006 Self::DEFAULT
5007 }
5008}
5009#[cfg_attr(feature = "ts", derive(TS))]
5010#[cfg_attr(feature = "ts", ts(export))]
5011#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5012#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5013#[cfg_attr(feature = "serde", serde(tag = "type"))]
5014#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5015#[repr(u32)]
5016#[doc = "Specifies the datatype of a MAVLink extended parameter."]
5017pub enum MavParamExtType {
5018 #[doc = "8-bit unsigned integer"]
5019 MAV_PARAM_EXT_TYPE_UINT8 = 1,
5020 #[doc = "8-bit signed integer"]
5021 MAV_PARAM_EXT_TYPE_INT8 = 2,
5022 #[doc = "16-bit unsigned integer"]
5023 MAV_PARAM_EXT_TYPE_UINT16 = 3,
5024 #[doc = "16-bit signed integer"]
5025 MAV_PARAM_EXT_TYPE_INT16 = 4,
5026 #[doc = "32-bit unsigned integer"]
5027 MAV_PARAM_EXT_TYPE_UINT32 = 5,
5028 #[doc = "32-bit signed integer"]
5029 MAV_PARAM_EXT_TYPE_INT32 = 6,
5030 #[doc = "64-bit unsigned integer"]
5031 MAV_PARAM_EXT_TYPE_UINT64 = 7,
5032 #[doc = "64-bit signed integer"]
5033 MAV_PARAM_EXT_TYPE_INT64 = 8,
5034 #[doc = "32-bit floating-point"]
5035 MAV_PARAM_EXT_TYPE_REAL32 = 9,
5036 #[doc = "64-bit floating-point"]
5037 MAV_PARAM_EXT_TYPE_REAL64 = 10,
5038 #[doc = "Custom Type"]
5039 MAV_PARAM_EXT_TYPE_CUSTOM = 11,
5040}
5041impl MavParamExtType {
5042 pub const DEFAULT: Self = Self::MAV_PARAM_EXT_TYPE_UINT8;
5043}
5044impl Default for MavParamExtType {
5045 fn default() -> Self {
5046 Self::DEFAULT
5047 }
5048}
5049#[cfg_attr(feature = "ts", derive(TS))]
5050#[cfg_attr(feature = "ts", ts(export))]
5051#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5052#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5053#[cfg_attr(feature = "serde", serde(tag = "type"))]
5054#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5055#[repr(u32)]
5056#[doc = "Specifies the datatype of a MAVLink parameter."]
5057pub enum MavParamType {
5058 #[doc = "8-bit unsigned integer"]
5059 MAV_PARAM_TYPE_UINT8 = 1,
5060 #[doc = "8-bit signed integer"]
5061 MAV_PARAM_TYPE_INT8 = 2,
5062 #[doc = "16-bit unsigned integer"]
5063 MAV_PARAM_TYPE_UINT16 = 3,
5064 #[doc = "16-bit signed integer"]
5065 MAV_PARAM_TYPE_INT16 = 4,
5066 #[doc = "32-bit unsigned integer"]
5067 MAV_PARAM_TYPE_UINT32 = 5,
5068 #[doc = "32-bit signed integer"]
5069 MAV_PARAM_TYPE_INT32 = 6,
5070 #[doc = "64-bit unsigned integer"]
5071 MAV_PARAM_TYPE_UINT64 = 7,
5072 #[doc = "64-bit signed integer"]
5073 MAV_PARAM_TYPE_INT64 = 8,
5074 #[doc = "32-bit floating-point"]
5075 MAV_PARAM_TYPE_REAL32 = 9,
5076 #[doc = "64-bit floating-point"]
5077 MAV_PARAM_TYPE_REAL64 = 10,
5078}
5079impl MavParamType {
5080 pub const DEFAULT: Self = Self::MAV_PARAM_TYPE_UINT8;
5081}
5082impl Default for MavParamType {
5083 fn default() -> Self {
5084 Self::DEFAULT
5085 }
5086}
5087bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Power supply status flags (bitmask)"] pub struct MavPowerStatus : u16 { # [doc = "main brick power supply valid"] const MAV_POWER_STATUS_BRICK_VALID = 1 ; # [doc = "main servo power supply valid for FMU"] const MAV_POWER_STATUS_SERVO_VALID = 2 ; # [doc = "USB power is connected"] const MAV_POWER_STATUS_USB_CONNECTED = 4 ; # [doc = "peripheral supply is in over-current state"] const MAV_POWER_STATUS_PERIPH_OVERCURRENT = 8 ; # [doc = "hi-power peripheral supply is in over-current state"] const MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT = 16 ; # [doc = "Power status has changed since boot"] const MAV_POWER_STATUS_CHANGED = 32 ; } }
5088impl MavPowerStatus {
5089 pub const DEFAULT: Self = Self::MAV_POWER_STATUS_BRICK_VALID;
5090}
5091impl Default for MavPowerStatus {
5092 fn default() -> Self {
5093 Self::DEFAULT
5094 }
5095}
5096bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability."] pub struct MavProtocolCapability : u64 { # [doc = "Autopilot supports the MISSION_ITEM float message type. Note that MISSION_ITEM is deprecated, and autopilots should use MISSION_INT instead."] const MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT = 1 ; # [deprecated = " See `MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CAST` (Deprecated since 2022-03)"] # [doc = "Autopilot supports the new param float message type."] const MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT = 2 ; # [doc = "Autopilot supports MISSION_ITEM_INT scaled integer message type. Note that this flag must always be set if missions are supported, because missions must always use MISSION_ITEM_INT (rather than MISSION_ITEM, which is deprecated)."] const MAV_PROTOCOL_CAPABILITY_MISSION_INT = 4 ; # [doc = "Autopilot supports COMMAND_INT scaled integer message type."] const MAV_PROTOCOL_CAPABILITY_COMMAND_INT = 8 ; # [doc = "Parameter protocol uses byte-wise encoding of parameter values into param_value (float) fields: <https://mavlink.io/en/services/parameter.html#parameter-encoding>. Note that either this flag or MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CAST should be set if the parameter protocol is supported."] const MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_BYTEWISE = 16 ; # [doc = "Autopilot supports the File Transfer Protocol v1: <https://mavlink.io/en/services/ftp.html>."] const MAV_PROTOCOL_CAPABILITY_FTP = 32 ; # [doc = "Autopilot supports commanding attitude offboard."] const MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET = 64 ; # [doc = "Autopilot supports commanding position and velocity targets in local NED frame."] const MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED = 128 ; # [doc = "Autopilot supports commanding position and velocity targets in global scaled integers."] const MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT = 256 ; # [doc = "Autopilot supports terrain protocol / data handling."] const MAV_PROTOCOL_CAPABILITY_TERRAIN = 512 ; # [doc = "Reserved for future use."] const MAV_PROTOCOL_CAPABILITY_RESERVED3 = 1024 ; # [doc = "Autopilot supports the MAV_CMD_DO_FLIGHTTERMINATION command (flight termination)."] const MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION = 2048 ; # [doc = "Autopilot supports onboard compass calibration."] const MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION = 4096 ; # [doc = "Autopilot supports MAVLink version 2."] const MAV_PROTOCOL_CAPABILITY_MAVLINK2 = 8192 ; # [doc = "Autopilot supports mission fence protocol."] const MAV_PROTOCOL_CAPABILITY_MISSION_FENCE = 16384 ; # [doc = "Autopilot supports mission rally point protocol."] const MAV_PROTOCOL_CAPABILITY_MISSION_RALLY = 32768 ; # [doc = "Reserved for future use."] const MAV_PROTOCOL_CAPABILITY_RESERVED2 = 65536 ; # [doc = "Parameter protocol uses C-cast of parameter values to set the param_value (float) fields: <https://mavlink.io/en/services/parameter.html#parameter-encoding>. Note that either this flag or MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_BYTEWISE should be set if the parameter protocol is supported."] const MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CAST = 131072 ; # [doc = "This component implements/is a gimbal manager. This means the GIMBAL_MANAGER_INFORMATION, and other messages can be requested."] const MAV_PROTOCOL_CAPABILITY_COMPONENT_IMPLEMENTS_GIMBAL_MANAGER = 262144 ; # [doc = "Component supports locking control to a particular GCS independent of its system (via MAV_CMD_REQUEST_OPERATOR_CONTROL)."] const MAV_PROTOCOL_CAPABILITY_COMPONENT_ACCEPTS_GCS_CONTROL = 524288 ; } }
5097impl MavProtocolCapability {
5098 pub const DEFAULT: Self = Self::MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT;
5099}
5100impl Default for MavProtocolCapability {
5101 fn default() -> Self {
5102 Self::DEFAULT
5103 }
5104}
5105#[cfg_attr(feature = "ts", derive(TS))]
5106#[cfg_attr(feature = "ts", ts(export))]
5107#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5108#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5109#[cfg_attr(feature = "serde", serde(tag = "type"))]
5110#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5111#[repr(u32)]
5112#[doc = "Result from a MAVLink command (MAV_CMD)"]
5113pub enum MavResult {
5114 #[doc = "Command is valid (is supported and has valid parameters), and was executed."]
5115 MAV_RESULT_ACCEPTED = 0,
5116 #[doc = "Command is valid, but cannot be executed at this time. This is used to indicate a problem that should be fixed just by waiting (e.g. a state machine is busy, can't arm because have not got GPS lock, etc.). Retrying later should work."]
5117 MAV_RESULT_TEMPORARILY_REJECTED = 1,
5118 #[doc = "Command is invalid (is supported but has invalid parameters). Retrying same command and parameters will not work."]
5119 MAV_RESULT_DENIED = 2,
5120 #[doc = "Command is not supported (unknown)."]
5121 MAV_RESULT_UNSUPPORTED = 3,
5122 #[doc = "Command is valid, but execution has failed. This is used to indicate any non-temporary or unexpected problem, i.e. any problem that must be fixed before the command can succeed/be retried. For example, attempting to write a file when out of memory, attempting to arm when sensors are not calibrated, etc."]
5123 MAV_RESULT_FAILED = 4,
5124 #[doc = "Command is valid and is being executed. This will be followed by further progress updates, i.e. the component may send further COMMAND_ACK messages with result MAV_RESULT_IN_PROGRESS (at a rate decided by the implementation), and must terminate by sending a COMMAND_ACK message with final result of the operation. The COMMAND_ACK.progress field can be used to indicate the progress of the operation."]
5125 MAV_RESULT_IN_PROGRESS = 5,
5126 #[doc = "Command has been cancelled (as a result of receiving a COMMAND_CANCEL message)."]
5127 MAV_RESULT_CANCELLED = 6,
5128 #[doc = "Command is only accepted when sent as a COMMAND_LONG."]
5129 MAV_RESULT_COMMAND_LONG_ONLY = 7,
5130 #[doc = "Command is only accepted when sent as a COMMAND_INT."]
5131 MAV_RESULT_COMMAND_INT_ONLY = 8,
5132 #[doc = "Command is invalid because a frame is required and the specified frame is not supported."]
5133 MAV_RESULT_COMMAND_UNSUPPORTED_MAV_FRAME = 9,
5134}
5135impl MavResult {
5136 pub const DEFAULT: Self = Self::MAV_RESULT_ACCEPTED;
5137}
5138impl Default for MavResult {
5139 fn default() -> Self {
5140 Self::DEFAULT
5141 }
5142}
5143#[cfg_attr(feature = "ts", derive(TS))]
5144#[cfg_attr(feature = "ts", ts(export))]
5145#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5146#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5147#[cfg_attr(feature = "serde", serde(tag = "type"))]
5148#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5149#[repr(u32)]
5150#[deprecated = " See `MAV_CMD_DO_SET_ROI_*` (Deprecated since 2018-01)"]
5151#[doc = "The ROI (region of interest) for the vehicle. This can be be used by the vehicle for camera/vehicle attitude alignment (see MAV_CMD_NAV_ROI)."]
5152pub enum MavRoi {
5153 #[doc = "No region of interest."]
5154 MAV_ROI_NONE = 0,
5155 #[doc = "Point toward next waypoint, with optional pitch/roll/yaw offset."]
5156 MAV_ROI_WPNEXT = 1,
5157 #[doc = "Point toward given waypoint."]
5158 MAV_ROI_WPINDEX = 2,
5159 #[doc = "Point toward fixed location."]
5160 MAV_ROI_LOCATION = 3,
5161 #[doc = "Point toward of given id."]
5162 MAV_ROI_TARGET = 4,
5163}
5164impl MavRoi {
5165 pub const DEFAULT: Self = Self::MAV_ROI_NONE;
5166}
5167impl Default for MavRoi {
5168 fn default() -> Self {
5169 Self::DEFAULT
5170 }
5171}
5172#[cfg_attr(feature = "ts", derive(TS))]
5173#[cfg_attr(feature = "ts", ts(export))]
5174#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5175#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5176#[cfg_attr(feature = "serde", serde(tag = "type"))]
5177#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5178#[repr(u32)]
5179#[doc = "Enumeration of sensor orientation, according to its rotations"]
5180pub enum MavSensorOrientation {
5181 #[doc = "Roll: 0, Pitch: 0, Yaw: 0"]
5182 MAV_SENSOR_ROTATION_NONE = 0,
5183 #[doc = "Roll: 0, Pitch: 0, Yaw: 45"]
5184 MAV_SENSOR_ROTATION_YAW_45 = 1,
5185 #[doc = "Roll: 0, Pitch: 0, Yaw: 90"]
5186 MAV_SENSOR_ROTATION_YAW_90 = 2,
5187 #[doc = "Roll: 0, Pitch: 0, Yaw: 135"]
5188 MAV_SENSOR_ROTATION_YAW_135 = 3,
5189 #[doc = "Roll: 0, Pitch: 0, Yaw: 180"]
5190 MAV_SENSOR_ROTATION_YAW_180 = 4,
5191 #[doc = "Roll: 0, Pitch: 0, Yaw: 225"]
5192 MAV_SENSOR_ROTATION_YAW_225 = 5,
5193 #[doc = "Roll: 0, Pitch: 0, Yaw: 270"]
5194 MAV_SENSOR_ROTATION_YAW_270 = 6,
5195 #[doc = "Roll: 0, Pitch: 0, Yaw: 315"]
5196 MAV_SENSOR_ROTATION_YAW_315 = 7,
5197 #[doc = "Roll: 180, Pitch: 0, Yaw: 0"]
5198 MAV_SENSOR_ROTATION_ROLL_180 = 8,
5199 #[doc = "Roll: 180, Pitch: 0, Yaw: 45"]
5200 MAV_SENSOR_ROTATION_ROLL_180_YAW_45 = 9,
5201 #[doc = "Roll: 180, Pitch: 0, Yaw: 90"]
5202 MAV_SENSOR_ROTATION_ROLL_180_YAW_90 = 10,
5203 #[doc = "Roll: 180, Pitch: 0, Yaw: 135"]
5204 MAV_SENSOR_ROTATION_ROLL_180_YAW_135 = 11,
5205 #[doc = "Roll: 0, Pitch: 180, Yaw: 0"]
5206 MAV_SENSOR_ROTATION_PITCH_180 = 12,
5207 #[doc = "Roll: 180, Pitch: 0, Yaw: 225"]
5208 MAV_SENSOR_ROTATION_ROLL_180_YAW_225 = 13,
5209 #[doc = "Roll: 180, Pitch: 0, Yaw: 270"]
5210 MAV_SENSOR_ROTATION_ROLL_180_YAW_270 = 14,
5211 #[doc = "Roll: 180, Pitch: 0, Yaw: 315"]
5212 MAV_SENSOR_ROTATION_ROLL_180_YAW_315 = 15,
5213 #[doc = "Roll: 90, Pitch: 0, Yaw: 0"]
5214 MAV_SENSOR_ROTATION_ROLL_90 = 16,
5215 #[doc = "Roll: 90, Pitch: 0, Yaw: 45"]
5216 MAV_SENSOR_ROTATION_ROLL_90_YAW_45 = 17,
5217 #[doc = "Roll: 90, Pitch: 0, Yaw: 90"]
5218 MAV_SENSOR_ROTATION_ROLL_90_YAW_90 = 18,
5219 #[doc = "Roll: 90, Pitch: 0, Yaw: 135"]
5220 MAV_SENSOR_ROTATION_ROLL_90_YAW_135 = 19,
5221 #[doc = "Roll: 270, Pitch: 0, Yaw: 0"]
5222 MAV_SENSOR_ROTATION_ROLL_270 = 20,
5223 #[doc = "Roll: 270, Pitch: 0, Yaw: 45"]
5224 MAV_SENSOR_ROTATION_ROLL_270_YAW_45 = 21,
5225 #[doc = "Roll: 270, Pitch: 0, Yaw: 90"]
5226 MAV_SENSOR_ROTATION_ROLL_270_YAW_90 = 22,
5227 #[doc = "Roll: 270, Pitch: 0, Yaw: 135"]
5228 MAV_SENSOR_ROTATION_ROLL_270_YAW_135 = 23,
5229 #[doc = "Roll: 0, Pitch: 90, Yaw: 0"]
5230 MAV_SENSOR_ROTATION_PITCH_90 = 24,
5231 #[doc = "Roll: 0, Pitch: 270, Yaw: 0"]
5232 MAV_SENSOR_ROTATION_PITCH_270 = 25,
5233 #[doc = "Roll: 0, Pitch: 180, Yaw: 90"]
5234 MAV_SENSOR_ROTATION_PITCH_180_YAW_90 = 26,
5235 #[doc = "Roll: 0, Pitch: 180, Yaw: 270"]
5236 MAV_SENSOR_ROTATION_PITCH_180_YAW_270 = 27,
5237 #[doc = "Roll: 90, Pitch: 90, Yaw: 0"]
5238 MAV_SENSOR_ROTATION_ROLL_90_PITCH_90 = 28,
5239 #[doc = "Roll: 180, Pitch: 90, Yaw: 0"]
5240 MAV_SENSOR_ROTATION_ROLL_180_PITCH_90 = 29,
5241 #[doc = "Roll: 270, Pitch: 90, Yaw: 0"]
5242 MAV_SENSOR_ROTATION_ROLL_270_PITCH_90 = 30,
5243 #[doc = "Roll: 90, Pitch: 180, Yaw: 0"]
5244 MAV_SENSOR_ROTATION_ROLL_90_PITCH_180 = 31,
5245 #[doc = "Roll: 270, Pitch: 180, Yaw: 0"]
5246 MAV_SENSOR_ROTATION_ROLL_270_PITCH_180 = 32,
5247 #[doc = "Roll: 90, Pitch: 270, Yaw: 0"]
5248 MAV_SENSOR_ROTATION_ROLL_90_PITCH_270 = 33,
5249 #[doc = "Roll: 180, Pitch: 270, Yaw: 0"]
5250 MAV_SENSOR_ROTATION_ROLL_180_PITCH_270 = 34,
5251 #[doc = "Roll: 270, Pitch: 270, Yaw: 0"]
5252 MAV_SENSOR_ROTATION_ROLL_270_PITCH_270 = 35,
5253 #[doc = "Roll: 90, Pitch: 180, Yaw: 90"]
5254 MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90 = 36,
5255 #[doc = "Roll: 90, Pitch: 0, Yaw: 270"]
5256 MAV_SENSOR_ROTATION_ROLL_90_YAW_270 = 37,
5257 #[doc = "Roll: 90, Pitch: 68, Yaw: 293"]
5258 MAV_SENSOR_ROTATION_ROLL_90_PITCH_68_YAW_293 = 38,
5259 #[doc = "Pitch: 315"]
5260 MAV_SENSOR_ROTATION_PITCH_315 = 39,
5261 #[doc = "Roll: 90, Pitch: 315"]
5262 MAV_SENSOR_ROTATION_ROLL_90_PITCH_315 = 40,
5263 #[doc = "Custom orientation"]
5264 MAV_SENSOR_ROTATION_CUSTOM = 100,
5265}
5266impl MavSensorOrientation {
5267 pub const DEFAULT: Self = Self::MAV_SENSOR_ROTATION_NONE;
5268}
5269impl Default for MavSensorOrientation {
5270 fn default() -> Self {
5271 Self::DEFAULT
5272 }
5273}
5274#[cfg_attr(feature = "ts", derive(TS))]
5275#[cfg_attr(feature = "ts", ts(export))]
5276#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5277#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5278#[cfg_attr(feature = "serde", serde(tag = "type"))]
5279#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5280#[repr(u32)]
5281#[doc = "Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: <http://www.kiwisyslog.com/kb/info:-syslog-message-levels/>."]
5282pub enum MavSeverity {
5283 #[doc = "System is unusable. This is a \"panic\" condition."]
5284 MAV_SEVERITY_EMERGENCY = 0,
5285 #[doc = "Action should be taken immediately. Indicates error in non-critical systems."]
5286 MAV_SEVERITY_ALERT = 1,
5287 #[doc = "Action must be taken immediately. Indicates failure in a primary system."]
5288 MAV_SEVERITY_CRITICAL = 2,
5289 #[doc = "Indicates an error in secondary/redundant systems."]
5290 MAV_SEVERITY_ERROR = 3,
5291 #[doc = "Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning."]
5292 MAV_SEVERITY_WARNING = 4,
5293 #[doc = "An unusual event has occurred, though not an error condition. This should be investigated for the root cause."]
5294 MAV_SEVERITY_NOTICE = 5,
5295 #[doc = "Normal operational messages. Useful for logging. No action is required for these messages."]
5296 MAV_SEVERITY_INFO = 6,
5297 #[doc = "Useful non-operational messages that can assist in debugging. These should not occur during normal operation."]
5298 MAV_SEVERITY_DEBUG = 7,
5299}
5300impl MavSeverity {
5301 pub const DEFAULT: Self = Self::MAV_SEVERITY_EMERGENCY;
5302}
5303impl Default for MavSeverity {
5304 fn default() -> Self {
5305 Self::DEFAULT
5306 }
5307}
5308#[cfg_attr(feature = "ts", derive(TS))]
5309#[cfg_attr(feature = "ts", ts(export))]
5310#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5311#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5312#[cfg_attr(feature = "serde", serde(tag = "type"))]
5313#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5314#[repr(u32)]
5315#[doc = "Standard modes with a well understood meaning across flight stacks and vehicle types. For example, most flight stack have the concept of a \"return\" or \"RTL\" mode that takes a vehicle to safety, even though the precise mechanics of this mode may differ. The modes supported by a flight stack can be queried using AVAILABLE_MODES and set using MAV_CMD_DO_SET_STANDARD_MODE. The current mode is streamed in CURRENT_MODE. See <https://mavlink.io/en/services/standard_modes.html>"]
5316pub enum MavStandardMode {
5317 #[doc = "Non standard mode. This may be used when reporting the mode if the current flight mode is not a standard mode."]
5318 MAV_STANDARD_MODE_NON_STANDARD = 0,
5319 #[doc = "Position mode (manual). Position-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold both position and altitude against wind and external forces. This mode can only be set by vehicles that can hold a fixed position. Multicopter (MC) vehicles actively brake and hold both position and altitude against wind and external forces. Hybrid MC/FW (\"VTOL\") vehicles first transition to multicopter mode (if needed) but otherwise behave in the same way as MC vehicles. Fixed-wing (FW) vehicles must not support this mode. Other vehicle types must not support this mode (this may be revisited through the PR process)."]
5320 MAV_STANDARD_MODE_POSITION_HOLD = 1,
5321 #[doc = "Orbit (manual). Position-controlled and stabilized manual mode. The vehicle circles around a fixed setpoint in the horizontal plane at a particular radius, altitude, and direction. Flight stacks may further allow manual control over the setpoint position, radius, direction, speed, and/or altitude of the circle, but this is not mandated. Flight stacks may support the [MAV_CMD_DO_ORBIT](<https://mavlink.io/en/messages/common.html#MAV_CMD_DO_ORBIT>) for changing the orbit parameters. MC and FW vehicles may support this mode. Hybrid MC/FW (\"VTOL\") vehicles may support this mode in MC/FW or both modes; if the mode is not supported by the current configuration the vehicle should transition to the supported configuration. Other vehicle types must not support this mode (this may be revisited through the PR process)."]
5322 MAV_STANDARD_MODE_ORBIT = 2,
5323 #[doc = "Cruise mode (manual). Position-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold their original track against wind and external forces. Fixed-wing (FW) vehicles level orientation and maintain current track and altitude against wind and external forces. Hybrid MC/FW (\"VTOL\") vehicles first transition to FW mode (if needed) but otherwise behave in the same way as MC vehicles. Multicopter (MC) vehicles must not support this mode. Other vehicle types must not support this mode (this may be revisited through the PR process)."]
5324 MAV_STANDARD_MODE_CRUISE = 3,
5325 #[doc = "Altitude hold (manual). Altitude-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold their altitude. MC vehicles continue with existing momentum and may move with wind (or other external forces). FW vehicles continue with current heading, but may be moved off-track by wind. Hybrid MC/FW (\"VTOL\") vehicles behave according to their current configuration/mode (FW or MC). Other vehicle types must not support this mode (this may be revisited through the PR process)."]
5326 MAV_STANDARD_MODE_ALTITUDE_HOLD = 4,
5327 #[doc = "Safe recovery mode (auto). Automatic mode that takes vehicle to a predefined safe location via a safe flight path, and may also automatically land the vehicle. This mode is more commonly referred to as RTL and/or or Smart RTL. The precise return location, flight path, and landing behaviour depend on vehicle configuration and type. For example, the vehicle might return to the home/launch location, a rally point, or the start of a mission landing, it might follow a direct path, mission path, or breadcrumb path, and land using a mission landing pattern or some other kind of descent."]
5328 MAV_STANDARD_MODE_SAFE_RECOVERY = 5,
5329 #[doc = "Mission mode (automatic). Automatic mode that executes MAVLink missions. Missions are executed from the current waypoint as soon as the mode is enabled."]
5330 MAV_STANDARD_MODE_MISSION = 6,
5331 #[doc = "Land mode (auto). Automatic mode that lands the vehicle at the current location. The precise landing behaviour depends on vehicle configuration and type."]
5332 MAV_STANDARD_MODE_LAND = 7,
5333 #[doc = "Takeoff mode (auto). Automatic takeoff mode. The precise takeoff behaviour depends on vehicle configuration and type."]
5334 MAV_STANDARD_MODE_TAKEOFF = 8,
5335}
5336impl MavStandardMode {
5337 pub const DEFAULT: Self = Self::MAV_STANDARD_MODE_NON_STANDARD;
5338}
5339impl Default for MavStandardMode {
5340 fn default() -> Self {
5341 Self::DEFAULT
5342 }
5343}
5344#[cfg_attr(feature = "ts", derive(TS))]
5345#[cfg_attr(feature = "ts", ts(export))]
5346#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5347#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5348#[cfg_attr(feature = "serde", serde(tag = "type"))]
5349#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5350#[repr(u32)]
5351pub enum MavState {
5352 #[doc = "Uninitialized system, state is unknown."]
5353 MAV_STATE_UNINIT = 0,
5354 #[doc = "System is booting up."]
5355 MAV_STATE_BOOT = 1,
5356 #[doc = "System is calibrating and not flight-ready."]
5357 MAV_STATE_CALIBRATING = 2,
5358 #[doc = "System is grounded and on standby. It can be launched any time."]
5359 MAV_STATE_STANDBY = 3,
5360 #[doc = "System is active and might be already airborne. Motors are engaged."]
5361 MAV_STATE_ACTIVE = 4,
5362 #[doc = "System is in a non-normal flight mode (failsafe). It can however still navigate."]
5363 MAV_STATE_CRITICAL = 5,
5364 #[doc = "System is in a non-normal flight mode (failsafe). It lost control over parts or over the whole airframe. It is in mayday and going down."]
5365 MAV_STATE_EMERGENCY = 6,
5366 #[doc = "System just initialized its power-down sequence, will shut down now."]
5367 MAV_STATE_POWEROFF = 7,
5368 #[doc = "System is terminating itself (failsafe or commanded)."]
5369 MAV_STATE_FLIGHT_TERMINATION = 8,
5370}
5371impl MavState {
5372 pub const DEFAULT: Self = Self::MAV_STATE_UNINIT;
5373}
5374impl Default for MavState {
5375 fn default() -> Self {
5376 Self::DEFAULT
5377 }
5378}
5379bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These encode the sensors whose status is sent as part of the SYS_STATUS message."] pub struct MavSysStatusSensor : u32 { # [doc = "0x01 3D gyro"] const MAV_SYS_STATUS_SENSOR_3D_GYRO = 1 ; # [doc = "0x02 3D accelerometer"] const MAV_SYS_STATUS_SENSOR_3D_ACCEL = 2 ; # [doc = "0x04 3D magnetometer"] const MAV_SYS_STATUS_SENSOR_3D_MAG = 4 ; # [doc = "0x08 absolute pressure"] const MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE = 8 ; # [doc = "0x10 differential pressure"] const MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE = 16 ; # [doc = "0x20 GPS"] const MAV_SYS_STATUS_SENSOR_GPS = 32 ; # [doc = "0x40 optical flow"] const MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW = 64 ; # [doc = "0x80 computer vision position"] const MAV_SYS_STATUS_SENSOR_VISION_POSITION = 128 ; # [doc = "0x100 laser based position"] const MAV_SYS_STATUS_SENSOR_LASER_POSITION = 256 ; # [doc = "0x200 external ground truth (Vicon or Leica)"] const MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH = 512 ; # [doc = "0x400 3D angular rate control"] const MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL = 1024 ; # [doc = "0x800 attitude stabilization"] const MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION = 2048 ; # [doc = "0x1000 yaw position"] const MAV_SYS_STATUS_SENSOR_YAW_POSITION = 4096 ; # [doc = "0x2000 z/altitude control"] const MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL = 8192 ; # [doc = "0x4000 x/y position control"] const MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL = 16384 ; # [doc = "0x8000 motor outputs / control"] const MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS = 32768 ; # [doc = "0x10000 RC receiver"] const MAV_SYS_STATUS_SENSOR_RC_RECEIVER = 65536 ; # [doc = "0x20000 2nd 3D gyro"] const MAV_SYS_STATUS_SENSOR_3D_GYRO2 = 131072 ; # [doc = "0x40000 2nd 3D accelerometer"] const MAV_SYS_STATUS_SENSOR_3D_ACCEL2 = 262144 ; # [doc = "0x80000 2nd 3D magnetometer"] const MAV_SYS_STATUS_SENSOR_3D_MAG2 = 524288 ; # [doc = "0x100000 geofence"] const MAV_SYS_STATUS_GEOFENCE = 1048576 ; # [doc = "0x200000 AHRS subsystem health"] const MAV_SYS_STATUS_AHRS = 2097152 ; # [doc = "0x400000 Terrain subsystem health"] const MAV_SYS_STATUS_TERRAIN = 4194304 ; # [doc = "0x800000 Motors are reversed"] const MAV_SYS_STATUS_REVERSE_MOTOR = 8388608 ; # [doc = "0x1000000 Logging"] const MAV_SYS_STATUS_LOGGING = 16777216 ; # [doc = "0x2000000 Battery"] const MAV_SYS_STATUS_SENSOR_BATTERY = 33554432 ; # [doc = "0x4000000 Proximity"] const MAV_SYS_STATUS_SENSOR_PROXIMITY = 67108864 ; # [doc = "0x8000000 Satellite Communication"] const MAV_SYS_STATUS_SENSOR_SATCOM = 134217728 ; # [doc = "0x10000000 pre-arm check status. Always healthy when armed"] const MAV_SYS_STATUS_PREARM_CHECK = 268435456 ; # [doc = "0x20000000 Avoidance/collision prevention"] const MAV_SYS_STATUS_OBSTACLE_AVOIDANCE = 536870912 ; # [doc = "0x40000000 propulsion (actuator, esc, motor or propellor)"] const MAV_SYS_STATUS_SENSOR_PROPULSION = 1073741824 ; # [doc = "0x80000000 Extended bit-field are used for further sensor status bits (needs to be set in onboard_control_sensors_present only)"] const MAV_SYS_STATUS_EXTENSION_USED = 2147483648 ; } }
5380impl MavSysStatusSensor {
5381 pub const DEFAULT: Self = Self::MAV_SYS_STATUS_SENSOR_3D_GYRO;
5382}
5383impl Default for MavSysStatusSensor {
5384 fn default() -> Self {
5385 Self::DEFAULT
5386 }
5387}
5388bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These encode the sensors whose status is sent as part of the SYS_STATUS message in the extended fields."] pub struct MavSysStatusSensorExtended : u32 { # [doc = "0x01 Recovery system (parachute, balloon, retracts etc)"] const MAV_SYS_STATUS_RECOVERY_SYSTEM = 1 ; } }
5389impl MavSysStatusSensorExtended {
5390 pub const DEFAULT: Self = Self::MAV_SYS_STATUS_RECOVERY_SYSTEM;
5391}
5392impl Default for MavSysStatusSensorExtended {
5393 fn default() -> Self {
5394 Self::DEFAULT
5395 }
5396}
5397#[cfg_attr(feature = "ts", derive(TS))]
5398#[cfg_attr(feature = "ts", ts(export))]
5399#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5400#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5401#[cfg_attr(feature = "serde", serde(tag = "type"))]
5402#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5403#[repr(u32)]
5404pub enum MavTunnelPayloadType {
5405 #[doc = "Encoding of payload unknown."]
5406 MAV_TUNNEL_PAYLOAD_TYPE_UNKNOWN = 0,
5407 #[doc = "Registered for STorM32 gimbal controller."]
5408 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED0 = 200,
5409 #[doc = "Registered for STorM32 gimbal controller."]
5410 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED1 = 201,
5411 #[doc = "Registered for STorM32 gimbal controller."]
5412 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED2 = 202,
5413 #[doc = "Registered for STorM32 gimbal controller."]
5414 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED3 = 203,
5415 #[doc = "Registered for STorM32 gimbal controller."]
5416 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED4 = 204,
5417 #[doc = "Registered for STorM32 gimbal controller."]
5418 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED5 = 205,
5419 #[doc = "Registered for STorM32 gimbal controller."]
5420 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED6 = 206,
5421 #[doc = "Registered for STorM32 gimbal controller."]
5422 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED7 = 207,
5423 #[doc = "Registered for STorM32 gimbal controller."]
5424 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED8 = 208,
5425 #[doc = "Registered for STorM32 gimbal controller."]
5426 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED9 = 209,
5427 #[doc = "Registered for ModalAI remote OSD protocol."]
5428 MAV_TUNNEL_PAYLOAD_TYPE_MODALAI_REMOTE_OSD = 210,
5429 #[doc = "Registered for ModalAI ESC UART passthru protocol."]
5430 MAV_TUNNEL_PAYLOAD_TYPE_MODALAI_ESC_UART_PASSTHRU = 211,
5431 #[doc = "Registered for ModalAI vendor use."]
5432 MAV_TUNNEL_PAYLOAD_TYPE_MODALAI_IO_UART_PASSTHRU = 212,
5433}
5434impl MavTunnelPayloadType {
5435 pub const DEFAULT: Self = Self::MAV_TUNNEL_PAYLOAD_TYPE_UNKNOWN;
5436}
5437impl Default for MavTunnelPayloadType {
5438 fn default() -> Self {
5439 Self::DEFAULT
5440 }
5441}
5442#[cfg_attr(feature = "ts", derive(TS))]
5443#[cfg_attr(feature = "ts", ts(export))]
5444#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5445#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5446#[cfg_attr(feature = "serde", serde(tag = "type"))]
5447#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5448#[repr(u32)]
5449#[doc = "MAVLINK component type reported in HEARTBEAT message. Flight controllers must report the type of the vehicle on which they are mounted (e.g. MAV_TYPE_OCTOROTOR). All other components must report a value appropriate for their type (e.g. a camera must use MAV_TYPE_CAMERA)."]
5450pub enum MavType {
5451 #[doc = "Generic micro air vehicle"]
5452 MAV_TYPE_GENERIC = 0,
5453 #[doc = "Fixed wing aircraft."]
5454 MAV_TYPE_FIXED_WING = 1,
5455 #[doc = "Quadrotor"]
5456 MAV_TYPE_QUADROTOR = 2,
5457 #[doc = "Coaxial helicopter"]
5458 MAV_TYPE_COAXIAL = 3,
5459 #[doc = "Normal helicopter with tail rotor."]
5460 MAV_TYPE_HELICOPTER = 4,
5461 #[doc = "Ground installation"]
5462 MAV_TYPE_ANTENNA_TRACKER = 5,
5463 #[doc = "Operator control unit / ground control station"]
5464 MAV_TYPE_GCS = 6,
5465 #[doc = "Airship, controlled"]
5466 MAV_TYPE_AIRSHIP = 7,
5467 #[doc = "Free balloon, uncontrolled"]
5468 MAV_TYPE_FREE_BALLOON = 8,
5469 #[doc = "Rocket"]
5470 MAV_TYPE_ROCKET = 9,
5471 #[doc = "Ground rover"]
5472 MAV_TYPE_GROUND_ROVER = 10,
5473 #[doc = "Surface vessel, boat, ship"]
5474 MAV_TYPE_SURFACE_BOAT = 11,
5475 #[doc = "Submarine"]
5476 MAV_TYPE_SUBMARINE = 12,
5477 #[doc = "Hexarotor"]
5478 MAV_TYPE_HEXAROTOR = 13,
5479 #[doc = "Octorotor"]
5480 MAV_TYPE_OCTOROTOR = 14,
5481 #[doc = "Tricopter"]
5482 MAV_TYPE_TRICOPTER = 15,
5483 #[doc = "Flapping wing"]
5484 MAV_TYPE_FLAPPING_WING = 16,
5485 #[doc = "Kite"]
5486 MAV_TYPE_KITE = 17,
5487 #[doc = "Onboard companion controller"]
5488 MAV_TYPE_ONBOARD_CONTROLLER = 18,
5489 #[doc = "Two-rotor Tailsitter VTOL that additionally uses control surfaces in vertical operation. Note, value previously named MAV_TYPE_VTOL_DUOROTOR."]
5490 MAV_TYPE_VTOL_TAILSITTER_DUOROTOR = 19,
5491 #[doc = "Quad-rotor Tailsitter VTOL using a V-shaped quad config in vertical operation. Note: value previously named MAV_TYPE_VTOL_QUADROTOR."]
5492 MAV_TYPE_VTOL_TAILSITTER_QUADROTOR = 20,
5493 #[doc = "Tiltrotor VTOL. Fuselage and wings stay (nominally) horizontal in all flight phases. It able to tilt (some) rotors to provide thrust in cruise flight."]
5494 MAV_TYPE_VTOL_TILTROTOR = 21,
5495 #[doc = "VTOL with separate fixed rotors for hover and cruise flight. Fuselage and wings stay (nominally) horizontal in all flight phases."]
5496 MAV_TYPE_VTOL_FIXEDROTOR = 22,
5497 #[doc = "Tailsitter VTOL. Fuselage and wings orientation changes depending on flight phase: vertical for hover, horizontal for cruise. Use more specific VTOL MAV_TYPE_VTOL_TAILSITTER_DUOROTOR or MAV_TYPE_VTOL_TAILSITTER_QUADROTOR if appropriate."]
5498 MAV_TYPE_VTOL_TAILSITTER = 23,
5499 #[doc = "Tiltwing VTOL. Fuselage stays horizontal in all flight phases. The whole wing, along with any attached engine, can tilt between vertical and horizontal mode."]
5500 MAV_TYPE_VTOL_TILTWING = 24,
5501 #[doc = "VTOL reserved 5"]
5502 MAV_TYPE_VTOL_RESERVED5 = 25,
5503 #[doc = "Gimbal"]
5504 MAV_TYPE_GIMBAL = 26,
5505 #[doc = "ADSB system"]
5506 MAV_TYPE_ADSB = 27,
5507 #[doc = "Steerable, nonrigid airfoil"]
5508 MAV_TYPE_PARAFOIL = 28,
5509 #[doc = "Dodecarotor"]
5510 MAV_TYPE_DODECAROTOR = 29,
5511 #[doc = "Camera"]
5512 MAV_TYPE_CAMERA = 30,
5513 #[doc = "Charging station"]
5514 MAV_TYPE_CHARGING_STATION = 31,
5515 #[doc = "FLARM collision avoidance system"]
5516 MAV_TYPE_FLARM = 32,
5517 #[doc = "Servo"]
5518 MAV_TYPE_SERVO = 33,
5519 #[doc = "Open Drone ID. See <https://mavlink.io/en/services/opendroneid.html>."]
5520 MAV_TYPE_ODID = 34,
5521 #[doc = "Decarotor"]
5522 MAV_TYPE_DECAROTOR = 35,
5523 #[doc = "Battery"]
5524 MAV_TYPE_BATTERY = 36,
5525 #[doc = "Parachute"]
5526 MAV_TYPE_PARACHUTE = 37,
5527 #[doc = "Log"]
5528 MAV_TYPE_LOG = 38,
5529 #[doc = "OSD"]
5530 MAV_TYPE_OSD = 39,
5531 #[doc = "IMU"]
5532 MAV_TYPE_IMU = 40,
5533 #[doc = "GPS"]
5534 MAV_TYPE_GPS = 41,
5535 #[doc = "Winch"]
5536 MAV_TYPE_WINCH = 42,
5537 #[doc = "Generic multirotor that does not fit into a specific type or whose type is unknown"]
5538 MAV_TYPE_GENERIC_MULTIROTOR = 43,
5539 #[doc = "Illuminator. An illuminator is a light source that is used for lighting up dark areas external to the sytstem: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light)."]
5540 MAV_TYPE_ILLUMINATOR = 44,
5541 #[doc = "Orbiter spacecraft. Includes satellites orbiting terrestrial and extra-terrestrial bodies. Follows NASA Spacecraft Classification."]
5542 MAV_TYPE_SPACECRAFT_ORBITER = 45,
5543}
5544impl MavType {
5545 pub const DEFAULT: Self = Self::MAV_TYPE_GENERIC;
5546}
5547impl Default for MavType {
5548 fn default() -> Self {
5549 Self::DEFAULT
5550 }
5551}
5552#[cfg_attr(feature = "ts", derive(TS))]
5553#[cfg_attr(feature = "ts", ts(export))]
5554#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5555#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5556#[cfg_attr(feature = "serde", serde(tag = "type"))]
5557#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5558#[repr(u32)]
5559#[doc = "Enumeration of VTOL states"]
5560pub enum MavVtolState {
5561 #[doc = "MAV is not configured as VTOL"]
5562 MAV_VTOL_STATE_UNDEFINED = 0,
5563 #[doc = "VTOL is in transition from multicopter to fixed-wing"]
5564 MAV_VTOL_STATE_TRANSITION_TO_FW = 1,
5565 #[doc = "VTOL is in transition from fixed-wing to multicopter"]
5566 MAV_VTOL_STATE_TRANSITION_TO_MC = 2,
5567 #[doc = "VTOL is in multicopter state"]
5568 MAV_VTOL_STATE_MC = 3,
5569 #[doc = "VTOL is in fixed-wing state"]
5570 MAV_VTOL_STATE_FW = 4,
5571}
5572impl MavVtolState {
5573 pub const DEFAULT: Self = Self::MAV_VTOL_STATE_UNDEFINED;
5574}
5575impl Default for MavVtolState {
5576 fn default() -> Self {
5577 Self::DEFAULT
5578 }
5579}
5580bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Winch status flags used in WINCH_STATUS"] pub struct MavWinchStatusFlag : u32 { # [doc = "Winch is healthy"] const MAV_WINCH_STATUS_HEALTHY = 1 ; # [doc = "Winch line is fully retracted"] const MAV_WINCH_STATUS_FULLY_RETRACTED = 2 ; # [doc = "Winch motor is moving"] const MAV_WINCH_STATUS_MOVING = 4 ; # [doc = "Winch clutch is engaged allowing motor to move freely."] const MAV_WINCH_STATUS_CLUTCH_ENGAGED = 8 ; # [doc = "Winch is locked by locking mechanism."] const MAV_WINCH_STATUS_LOCKED = 16 ; # [doc = "Winch is gravity dropping payload."] const MAV_WINCH_STATUS_DROPPING = 32 ; # [doc = "Winch is arresting payload descent."] const MAV_WINCH_STATUS_ARRESTING = 64 ; # [doc = "Winch is using torque measurements to sense the ground."] const MAV_WINCH_STATUS_GROUND_SENSE = 128 ; # [doc = "Winch is returning to the fully retracted position."] const MAV_WINCH_STATUS_RETRACTING = 256 ; # [doc = "Winch is redelivering the payload. This is a failover state if the line tension goes above a threshold during RETRACTING."] const MAV_WINCH_STATUS_REDELIVER = 512 ; # [doc = "Winch is abandoning the line and possibly payload. Winch unspools the entire calculated line length. This is a failover state from REDELIVER if the number of attempts exceeds a threshold."] const MAV_WINCH_STATUS_ABANDON_LINE = 1024 ; # [doc = "Winch is engaging the locking mechanism."] const MAV_WINCH_STATUS_LOCKING = 2048 ; # [doc = "Winch is spooling on line."] const MAV_WINCH_STATUS_LOAD_LINE = 4096 ; # [doc = "Winch is loading a payload."] const MAV_WINCH_STATUS_LOAD_PAYLOAD = 8192 ; } }
5581impl MavWinchStatusFlag {
5582 pub const DEFAULT: Self = Self::MAV_WINCH_STATUS_HEALTHY;
5583}
5584impl Default for MavWinchStatusFlag {
5585 fn default() -> Self {
5586 Self::DEFAULT
5587 }
5588}
5589#[cfg_attr(feature = "ts", derive(TS))]
5590#[cfg_attr(feature = "ts", ts(export))]
5591#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5592#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5593#[cfg_attr(feature = "serde", serde(tag = "type"))]
5594#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5595#[repr(u32)]
5596pub enum MavlinkDataStreamType {
5597 MAVLINK_DATA_STREAM_IMG_JPEG = 0,
5598 MAVLINK_DATA_STREAM_IMG_BMP = 1,
5599 MAVLINK_DATA_STREAM_IMG_RAW8U = 2,
5600 MAVLINK_DATA_STREAM_IMG_RAW32U = 3,
5601 MAVLINK_DATA_STREAM_IMG_PGM = 4,
5602 MAVLINK_DATA_STREAM_IMG_PNG = 5,
5603}
5604impl MavlinkDataStreamType {
5605 pub const DEFAULT: Self = Self::MAVLINK_DATA_STREAM_IMG_JPEG;
5606}
5607impl Default for MavlinkDataStreamType {
5608 fn default() -> Self {
5609 Self::DEFAULT
5610 }
5611}
5612#[cfg_attr(feature = "ts", derive(TS))]
5613#[cfg_attr(feature = "ts", ts(export))]
5614#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5615#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5616#[cfg_attr(feature = "serde", serde(tag = "type"))]
5617#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5618#[repr(u32)]
5619#[doc = "States of the mission state machine. Note that these states are independent of whether the mission is in a mode that can execute mission items or not (is suspended). They may not all be relevant on all vehicles."]
5620pub enum MissionState {
5621 #[doc = "The mission status reporting is not supported."]
5622 MISSION_STATE_UNKNOWN = 0,
5623 #[doc = "No mission on the vehicle."]
5624 MISSION_STATE_NO_MISSION = 1,
5625 #[doc = "Mission has not started. This is the case after a mission has uploaded but not yet started executing."]
5626 MISSION_STATE_NOT_STARTED = 2,
5627 #[doc = "Mission is active, and will execute mission items when in auto mode."]
5628 MISSION_STATE_ACTIVE = 3,
5629 #[doc = "Mission is paused when in auto mode."]
5630 MISSION_STATE_PAUSED = 4,
5631 #[doc = "Mission has executed all mission items."]
5632 MISSION_STATE_COMPLETE = 5,
5633}
5634impl MissionState {
5635 pub const DEFAULT: Self = Self::MISSION_STATE_UNKNOWN;
5636}
5637impl Default for MissionState {
5638 fn default() -> Self {
5639 Self::DEFAULT
5640 }
5641}
5642#[cfg_attr(feature = "ts", derive(TS))]
5643#[cfg_attr(feature = "ts", ts(export))]
5644#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5645#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5646#[cfg_attr(feature = "serde", serde(tag = "type"))]
5647#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5648#[repr(u32)]
5649#[doc = "Sequence that motors are tested when using MAV_CMD_DO_MOTOR_TEST."]
5650pub enum MotorTestOrder {
5651 #[doc = "Default autopilot motor test method."]
5652 MOTOR_TEST_ORDER_DEFAULT = 0,
5653 #[doc = "Motor numbers are specified as their index in a predefined vehicle-specific sequence."]
5654 MOTOR_TEST_ORDER_SEQUENCE = 1,
5655 #[doc = "Motor numbers are specified as the output as labeled on the board."]
5656 MOTOR_TEST_ORDER_BOARD = 2,
5657}
5658impl MotorTestOrder {
5659 pub const DEFAULT: Self = Self::MOTOR_TEST_ORDER_DEFAULT;
5660}
5661impl Default for MotorTestOrder {
5662 fn default() -> Self {
5663 Self::DEFAULT
5664 }
5665}
5666#[cfg_attr(feature = "ts", derive(TS))]
5667#[cfg_attr(feature = "ts", ts(export))]
5668#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5669#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5670#[cfg_attr(feature = "serde", serde(tag = "type"))]
5671#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5672#[repr(u32)]
5673#[doc = "Defines how throttle value is represented in MAV_CMD_DO_MOTOR_TEST."]
5674pub enum MotorTestThrottleType {
5675 #[doc = "Throttle as a percentage (0 ~ 100)"]
5676 MOTOR_TEST_THROTTLE_PERCENT = 0,
5677 #[doc = "Throttle as an absolute PWM value (normally in range of 1000~2000)."]
5678 MOTOR_TEST_THROTTLE_PWM = 1,
5679 #[doc = "Throttle pass-through from pilot's transmitter."]
5680 MOTOR_TEST_THROTTLE_PILOT = 2,
5681 #[doc = "Per-motor compass calibration test."]
5682 MOTOR_TEST_COMPASS_CAL = 3,
5683}
5684impl MotorTestThrottleType {
5685 pub const DEFAULT: Self = Self::MOTOR_TEST_THROTTLE_PERCENT;
5686}
5687impl Default for MotorTestThrottleType {
5688 fn default() -> Self {
5689 Self::DEFAULT
5690 }
5691}
5692#[cfg_attr(feature = "ts", derive(TS))]
5693#[cfg_attr(feature = "ts", ts(export))]
5694#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5695#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5696#[cfg_attr(feature = "serde", serde(tag = "type"))]
5697#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5698#[repr(u32)]
5699pub enum NavVtolLandOptions {
5700 #[doc = "Default autopilot landing behaviour."]
5701 NAV_VTOL_LAND_OPTIONS_DEFAULT = 0,
5702 #[doc = "Descend in fixed wing mode, transitioning to multicopter mode for vertical landing when close to the ground. The fixed wing descent pattern is at the discretion of the vehicle (e.g. transition altitude, loiter direction, radius, and speed, etc.)."]
5703 NAV_VTOL_LAND_OPTIONS_FW_DESCENT = 1,
5704 #[doc = "Land in multicopter mode on reaching the landing coordinates (the whole landing is by \"hover descent\")."]
5705 NAV_VTOL_LAND_OPTIONS_HOVER_DESCENT = 2,
5706}
5707impl NavVtolLandOptions {
5708 pub const DEFAULT: Self = Self::NAV_VTOL_LAND_OPTIONS_DEFAULT;
5709}
5710impl Default for NavVtolLandOptions {
5711 fn default() -> Self {
5712 Self::DEFAULT
5713 }
5714}
5715#[cfg_attr(feature = "ts", derive(TS))]
5716#[cfg_attr(feature = "ts", ts(export))]
5717#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5718#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5719#[cfg_attr(feature = "serde", serde(tag = "type"))]
5720#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5721#[repr(u32)]
5722#[doc = "Yaw behaviour during orbit flight."]
5723pub enum OrbitYawBehaviour {
5724 #[doc = "Vehicle front points to the center (default)."]
5725 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER = 0,
5726 #[doc = "Vehicle front holds heading when message received."]
5727 ORBIT_YAW_BEHAVIOUR_HOLD_INITIAL_HEADING = 1,
5728 #[doc = "Yaw uncontrolled."]
5729 ORBIT_YAW_BEHAVIOUR_UNCONTROLLED = 2,
5730 #[doc = "Vehicle front follows flight path (tangential to circle)."]
5731 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TANGENT_TO_CIRCLE = 3,
5732 #[doc = "Yaw controlled by RC input."]
5733 ORBIT_YAW_BEHAVIOUR_RC_CONTROLLED = 4,
5734 #[doc = "Vehicle uses current yaw behaviour (unchanged). The vehicle-default yaw behaviour is used if this value is specified when orbit is first commanded."]
5735 ORBIT_YAW_BEHAVIOUR_UNCHANGED = 5,
5736}
5737impl OrbitYawBehaviour {
5738 pub const DEFAULT: Self = Self::ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER;
5739}
5740impl Default for OrbitYawBehaviour {
5741 fn default() -> Self {
5742 Self::DEFAULT
5743 }
5744}
5745#[cfg_attr(feature = "ts", derive(TS))]
5746#[cfg_attr(feature = "ts", ts(export))]
5747#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5748#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5749#[cfg_attr(feature = "serde", serde(tag = "type"))]
5750#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5751#[repr(u32)]
5752#[doc = "Parachute actions. Trigger release and enable/disable auto-release."]
5753pub enum ParachuteAction {
5754 #[doc = "Disable auto-release of parachute (i.e. release triggered by crash detectors)."]
5755 PARACHUTE_DISABLE = 0,
5756 #[doc = "Enable auto-release of parachute."]
5757 PARACHUTE_ENABLE = 1,
5758 #[doc = "Release parachute and kill motors."]
5759 PARACHUTE_RELEASE = 2,
5760}
5761impl ParachuteAction {
5762 pub const DEFAULT: Self = Self::PARACHUTE_DISABLE;
5763}
5764impl Default for ParachuteAction {
5765 fn default() -> Self {
5766 Self::DEFAULT
5767 }
5768}
5769#[cfg_attr(feature = "ts", derive(TS))]
5770#[cfg_attr(feature = "ts", ts(export))]
5771#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5772#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5773#[cfg_attr(feature = "serde", serde(tag = "type"))]
5774#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5775#[repr(u32)]
5776#[doc = "Result from PARAM_EXT_SET message."]
5777pub enum ParamAck {
5778 #[doc = "Parameter value ACCEPTED and SET"]
5779 PARAM_ACK_ACCEPTED = 0,
5780 #[doc = "Parameter value UNKNOWN/UNSUPPORTED"]
5781 PARAM_ACK_VALUE_UNSUPPORTED = 1,
5782 #[doc = "Parameter failed to set"]
5783 PARAM_ACK_FAILED = 2,
5784 #[doc = "Parameter value received but not yet set/accepted. A subsequent PARAM_EXT_ACK with the final result will follow once operation is completed. This is returned immediately for parameters that take longer to set, indicating that the the parameter was received and does not need to be resent."]
5785 PARAM_ACK_IN_PROGRESS = 3,
5786}
5787impl ParamAck {
5788 pub const DEFAULT: Self = Self::PARAM_ACK_ACCEPTED;
5789}
5790impl Default for ParamAck {
5791 fn default() -> Self {
5792 Self::DEFAULT
5793 }
5794}
5795bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 9 is set the floats afx afy afz should be interpreted as force instead of acceleration."] pub struct PositionTargetTypemask : u16 { # [doc = "Ignore position x"] const POSITION_TARGET_TYPEMASK_X_IGNORE = 1 ; # [doc = "Ignore position y"] const POSITION_TARGET_TYPEMASK_Y_IGNORE = 2 ; # [doc = "Ignore position z"] const POSITION_TARGET_TYPEMASK_Z_IGNORE = 4 ; # [doc = "Ignore velocity x"] const POSITION_TARGET_TYPEMASK_VX_IGNORE = 8 ; # [doc = "Ignore velocity y"] const POSITION_TARGET_TYPEMASK_VY_IGNORE = 16 ; # [doc = "Ignore velocity z"] const POSITION_TARGET_TYPEMASK_VZ_IGNORE = 32 ; # [doc = "Ignore acceleration x"] const POSITION_TARGET_TYPEMASK_AX_IGNORE = 64 ; # [doc = "Ignore acceleration y"] const POSITION_TARGET_TYPEMASK_AY_IGNORE = 128 ; # [doc = "Ignore acceleration z"] const POSITION_TARGET_TYPEMASK_AZ_IGNORE = 256 ; # [doc = "Use force instead of acceleration"] const POSITION_TARGET_TYPEMASK_FORCE_SET = 512 ; # [doc = "Ignore yaw"] const POSITION_TARGET_TYPEMASK_YAW_IGNORE = 1024 ; # [doc = "Ignore yaw rate"] const POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE = 2048 ; } }
5796impl PositionTargetTypemask {
5797 pub const DEFAULT: Self = Self::POSITION_TARGET_TYPEMASK_X_IGNORE;
5798}
5799impl Default for PositionTargetTypemask {
5800 fn default() -> Self {
5801 Self::DEFAULT
5802 }
5803}
5804#[cfg_attr(feature = "ts", derive(TS))]
5805#[cfg_attr(feature = "ts", ts(export))]
5806#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5807#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5808#[cfg_attr(feature = "serde", serde(tag = "type"))]
5809#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5810#[repr(u32)]
5811#[doc = "Precision land modes (used in MAV_CMD_NAV_LAND)."]
5812pub enum PrecisionLandMode {
5813 #[doc = "Normal (non-precision) landing."]
5814 PRECISION_LAND_MODE_DISABLED = 0,
5815 #[doc = "Use precision landing if beacon detected when land command accepted, otherwise land normally."]
5816 PRECISION_LAND_MODE_OPPORTUNISTIC = 1,
5817 #[doc = "Use precision landing, searching for beacon if not found when land command accepted (land normally if beacon cannot be found)."]
5818 PRECISION_LAND_MODE_REQUIRED = 2,
5819}
5820impl PrecisionLandMode {
5821 pub const DEFAULT: Self = Self::PRECISION_LAND_MODE_DISABLED;
5822}
5823impl Default for PrecisionLandMode {
5824 fn default() -> Self {
5825 Self::DEFAULT
5826 }
5827}
5828#[cfg_attr(feature = "ts", derive(TS))]
5829#[cfg_attr(feature = "ts", ts(export))]
5830#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5831#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5832#[cfg_attr(feature = "serde", serde(tag = "type"))]
5833#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5834#[repr(u32)]
5835#[doc = "Actions for reading and writing plan information (mission, rally points, geofence) between persistent and volatile storage when using MAV_CMD_PREFLIGHT_STORAGE. (Commonly missions are loaded from persistent storage (flash/EEPROM) into volatile storage (RAM) on startup and written back when they are changed.)"]
5836pub enum PreflightStorageMissionAction {
5837 #[doc = "Read current mission data from persistent storage"]
5838 MISSION_READ_PERSISTENT = 0,
5839 #[doc = "Write current mission data to persistent storage"]
5840 MISSION_WRITE_PERSISTENT = 1,
5841 #[doc = "Erase all mission data stored on the vehicle (both persistent and volatile storage)"]
5842 MISSION_RESET_DEFAULT = 2,
5843}
5844impl PreflightStorageMissionAction {
5845 pub const DEFAULT: Self = Self::MISSION_READ_PERSISTENT;
5846}
5847impl Default for PreflightStorageMissionAction {
5848 fn default() -> Self {
5849 Self::DEFAULT
5850 }
5851}
5852#[cfg_attr(feature = "ts", derive(TS))]
5853#[cfg_attr(feature = "ts", ts(export))]
5854#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5855#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5856#[cfg_attr(feature = "serde", serde(tag = "type"))]
5857#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5858#[repr(u32)]
5859#[doc = "Actions for reading/writing parameters between persistent and volatile storage when using MAV_CMD_PREFLIGHT_STORAGE. (Commonly parameters are loaded from persistent storage (flash/EEPROM) into volatile storage (RAM) on startup and written back when they are changed.)"]
5860pub enum PreflightStorageParameterAction {
5861 #[doc = "Read all parameters from persistent storage. Replaces values in volatile storage."]
5862 PARAM_READ_PERSISTENT = 0,
5863 #[doc = "Write all parameter values to persistent storage (flash/EEPROM)"]
5864 PARAM_WRITE_PERSISTENT = 1,
5865 #[doc = "Reset all user configurable parameters to their default value (including airframe selection, sensor calibration data, safety settings, and so on). Does not reset values that contain operation counters and vehicle computed statistics."]
5866 PARAM_RESET_CONFIG_DEFAULT = 2,
5867 #[doc = "Reset only sensor calibration parameters to factory defaults (or firmware default if not available)"]
5868 PARAM_RESET_SENSOR_DEFAULT = 3,
5869 #[doc = "Reset all parameters, including operation counters, to default values"]
5870 PARAM_RESET_ALL_DEFAULT = 4,
5871}
5872impl PreflightStorageParameterAction {
5873 pub const DEFAULT: Self = Self::PARAM_READ_PERSISTENT;
5874}
5875impl Default for PreflightStorageParameterAction {
5876 fn default() -> Self {
5877 Self::DEFAULT
5878 }
5879}
5880#[cfg_attr(feature = "ts", derive(TS))]
5881#[cfg_attr(feature = "ts", ts(export))]
5882#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5883#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5884#[cfg_attr(feature = "serde", serde(tag = "type"))]
5885#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5886#[repr(u32)]
5887#[doc = "RC sub-type of types defined in RC_TYPE. Used in MAV_CMD_START_RX_PAIR. Ignored if value does not correspond to the set RC_TYPE."]
5888pub enum RcSubType {
5889 #[doc = "Spektrum DSM2"]
5890 RC_SUB_TYPE_SPEKTRUM_DSM2 = 0,
5891 #[doc = "Spektrum DSMX"]
5892 RC_SUB_TYPE_SPEKTRUM_DSMX = 1,
5893 #[doc = "Spektrum DSMX8"]
5894 RC_SUB_TYPE_SPEKTRUM_DSMX8 = 2,
5895}
5896impl RcSubType {
5897 pub const DEFAULT: Self = Self::RC_SUB_TYPE_SPEKTRUM_DSM2;
5898}
5899impl Default for RcSubType {
5900 fn default() -> Self {
5901 Self::DEFAULT
5902 }
5903}
5904#[cfg_attr(feature = "ts", derive(TS))]
5905#[cfg_attr(feature = "ts", ts(export))]
5906#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5907#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5908#[cfg_attr(feature = "serde", serde(tag = "type"))]
5909#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5910#[repr(u32)]
5911#[doc = "RC type. Used in MAV_CMD_START_RX_PAIR."]
5912pub enum RcType {
5913 #[doc = "Spektrum"]
5914 RC_TYPE_SPEKTRUM = 0,
5915 #[doc = "CRSF"]
5916 RC_TYPE_CRSF = 1,
5917}
5918impl RcType {
5919 pub const DEFAULT: Self = Self::RC_TYPE_SPEKTRUM;
5920}
5921impl Default for RcType {
5922 fn default() -> Self {
5923 Self::DEFAULT
5924 }
5925}
5926#[cfg_attr(feature = "ts", derive(TS))]
5927#[cfg_attr(feature = "ts", ts(export))]
5928#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5929#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5930#[cfg_attr(feature = "serde", serde(tag = "type"))]
5931#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5932#[repr(u32)]
5933#[doc = "Specifies the conditions under which the MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN command should be accepted."]
5934pub enum RebootShutdownConditions {
5935 #[doc = "Reboot/Shutdown only if allowed by safety checks, such as being landed."]
5936 REBOOT_SHUTDOWN_CONDITIONS_SAFETY_INTERLOCKED = 0,
5937 #[doc = "Force reboot/shutdown of the autopilot/component regardless of system state."]
5938 REBOOT_SHUTDOWN_CONDITIONS_FORCE = 20190226,
5939}
5940impl RebootShutdownConditions {
5941 pub const DEFAULT: Self = Self::REBOOT_SHUTDOWN_CONDITIONS_SAFETY_INTERLOCKED;
5942}
5943impl Default for RebootShutdownConditions {
5944 fn default() -> Self {
5945 Self::DEFAULT
5946 }
5947}
5948#[cfg_attr(feature = "ts", derive(TS))]
5949#[cfg_attr(feature = "ts", ts(export))]
5950#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5951#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5952#[cfg_attr(feature = "serde", serde(tag = "type"))]
5953#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5954#[repr(u32)]
5955#[doc = "RTK GPS baseline coordinate system, used for RTK corrections"]
5956pub enum RtkBaselineCoordinateSystem {
5957 #[doc = "Earth-centered, Earth-fixed"]
5958 RTK_BASELINE_COORDINATE_SYSTEM_ECEF = 0,
5959 #[doc = "RTK basestation centered, north, east, down"]
5960 RTK_BASELINE_COORDINATE_SYSTEM_NED = 1,
5961}
5962impl RtkBaselineCoordinateSystem {
5963 pub const DEFAULT: Self = Self::RTK_BASELINE_COORDINATE_SYSTEM_ECEF;
5964}
5965impl Default for RtkBaselineCoordinateSystem {
5966 fn default() -> Self {
5967 Self::DEFAULT
5968 }
5969}
5970#[cfg_attr(feature = "ts", derive(TS))]
5971#[cfg_attr(feature = "ts", ts(export))]
5972#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5973#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5974#[cfg_attr(feature = "serde", serde(tag = "type"))]
5975#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5976#[repr(u32)]
5977#[doc = "Possible safety switch states."]
5978pub enum SafetySwitchState {
5979 #[doc = "Safety switch is engaged and vehicle should be safe to approach."]
5980 SAFETY_SWITCH_STATE_SAFE = 0,
5981 #[doc = "Safety switch is NOT engaged and motors, propellers and other actuators should be considered active."]
5982 SAFETY_SWITCH_STATE_DANGEROUS = 1,
5983}
5984impl SafetySwitchState {
5985 pub const DEFAULT: Self = Self::SAFETY_SWITCH_STATE_SAFE;
5986}
5987impl Default for SafetySwitchState {
5988 fn default() -> Self {
5989 Self::DEFAULT
5990 }
5991}
5992#[cfg_attr(feature = "ts", derive(TS))]
5993#[cfg_attr(feature = "ts", ts(export))]
5994#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
5995#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5996#[cfg_attr(feature = "serde", serde(tag = "type"))]
5997#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5998#[repr(u32)]
5999#[doc = "SERIAL_CONTROL device types"]
6000pub enum SerialControlDev {
6001 #[doc = "First telemetry port"]
6002 SERIAL_CONTROL_DEV_TELEM1 = 0,
6003 #[doc = "Second telemetry port"]
6004 SERIAL_CONTROL_DEV_TELEM2 = 1,
6005 #[doc = "First GPS port"]
6006 SERIAL_CONTROL_DEV_GPS1 = 2,
6007 #[doc = "Second GPS port"]
6008 SERIAL_CONTROL_DEV_GPS2 = 3,
6009 #[doc = "system shell"]
6010 SERIAL_CONTROL_DEV_SHELL = 10,
6011 #[doc = "SERIAL0"]
6012 SERIAL_CONTROL_SERIAL0 = 100,
6013 #[doc = "SERIAL1"]
6014 SERIAL_CONTROL_SERIAL1 = 101,
6015 #[doc = "SERIAL2"]
6016 SERIAL_CONTROL_SERIAL2 = 102,
6017 #[doc = "SERIAL3"]
6018 SERIAL_CONTROL_SERIAL3 = 103,
6019 #[doc = "SERIAL4"]
6020 SERIAL_CONTROL_SERIAL4 = 104,
6021 #[doc = "SERIAL5"]
6022 SERIAL_CONTROL_SERIAL5 = 105,
6023 #[doc = "SERIAL6"]
6024 SERIAL_CONTROL_SERIAL6 = 106,
6025 #[doc = "SERIAL7"]
6026 SERIAL_CONTROL_SERIAL7 = 107,
6027 #[doc = "SERIAL8"]
6028 SERIAL_CONTROL_SERIAL8 = 108,
6029 #[doc = "SERIAL9"]
6030 SERIAL_CONTROL_SERIAL9 = 109,
6031}
6032impl SerialControlDev {
6033 pub const DEFAULT: Self = Self::SERIAL_CONTROL_DEV_TELEM1;
6034}
6035impl Default for SerialControlDev {
6036 fn default() -> Self {
6037 Self::DEFAULT
6038 }
6039}
6040bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "SERIAL_CONTROL flags (bitmask)"] pub struct SerialControlFlag : u8 { # [doc = "Set if this is a reply"] const SERIAL_CONTROL_FLAG_REPLY = 1 ; # [doc = "Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message"] const SERIAL_CONTROL_FLAG_RESPOND = 2 ; # [doc = "Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set"] const SERIAL_CONTROL_FLAG_EXCLUSIVE = 4 ; # [doc = "Block on writes to the serial port"] const SERIAL_CONTROL_FLAG_BLOCKING = 8 ; # [doc = "Send multiple replies until port is drained"] const SERIAL_CONTROL_FLAG_MULTI = 16 ; } }
6041impl SerialControlFlag {
6042 pub const DEFAULT: Self = Self::SERIAL_CONTROL_FLAG_REPLY;
6043}
6044impl Default for SerialControlFlag {
6045 fn default() -> Self {
6046 Self::DEFAULT
6047 }
6048}
6049#[cfg_attr(feature = "ts", derive(TS))]
6050#[cfg_attr(feature = "ts", ts(export))]
6051#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
6052#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6053#[cfg_attr(feature = "serde", serde(tag = "type"))]
6054#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6055#[repr(u32)]
6056#[doc = "Focus types for MAV_CMD_SET_CAMERA_FOCUS"]
6057pub enum SetFocusType {
6058 #[doc = "Focus one step increment (-1 for focusing in, 1 for focusing out towards infinity)."]
6059 FOCUS_TYPE_STEP = 0,
6060 #[doc = "Continuous normalized focus in/out rate until stopped. Range -1..1, negative: in, positive: out towards infinity, 0 to stop focusing. Other values should be clipped to the range."]
6061 FOCUS_TYPE_CONTINUOUS = 1,
6062 #[doc = "Focus value as proportion of full camera focus range (a value between 0.0 and 100.0)"]
6063 FOCUS_TYPE_RANGE = 2,
6064 #[doc = "Focus value in metres. Note that there is no message to get the valid focus range of the camera, so this can type can only be used for cameras where the range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera)."]
6065 FOCUS_TYPE_METERS = 3,
6066 #[doc = "Focus automatically."]
6067 FOCUS_TYPE_AUTO = 4,
6068 #[doc = "Single auto focus. Mainly used for still pictures. Usually abbreviated as AF-S."]
6069 FOCUS_TYPE_AUTO_SINGLE = 5,
6070 #[doc = "Continuous auto focus. Mainly used for dynamic scenes. Abbreviated as AF-C."]
6071 FOCUS_TYPE_AUTO_CONTINUOUS = 6,
6072}
6073impl SetFocusType {
6074 pub const DEFAULT: Self = Self::FOCUS_TYPE_STEP;
6075}
6076impl Default for SetFocusType {
6077 fn default() -> Self {
6078 Self::DEFAULT
6079 }
6080}
6081#[cfg_attr(feature = "ts", derive(TS))]
6082#[cfg_attr(feature = "ts", ts(export))]
6083#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
6084#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6085#[cfg_attr(feature = "serde", serde(tag = "type"))]
6086#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6087#[repr(u32)]
6088#[doc = "Speed setpoint types used in MAV_CMD_DO_CHANGE_SPEED"]
6089pub enum SpeedType {
6090 #[doc = "Airspeed"]
6091 SPEED_TYPE_AIRSPEED = 0,
6092 #[doc = "Groundspeed"]
6093 SPEED_TYPE_GROUNDSPEED = 1,
6094 #[doc = "Climb speed"]
6095 SPEED_TYPE_CLIMB_SPEED = 2,
6096 #[doc = "Descent speed"]
6097 SPEED_TYPE_DESCENT_SPEED = 3,
6098}
6099impl SpeedType {
6100 pub const DEFAULT: Self = Self::SPEED_TYPE_AIRSPEED;
6101}
6102impl Default for SpeedType {
6103 fn default() -> Self {
6104 Self::DEFAULT
6105 }
6106}
6107#[cfg_attr(feature = "ts", derive(TS))]
6108#[cfg_attr(feature = "ts", ts(export))]
6109#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
6110#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6111#[cfg_attr(feature = "serde", serde(tag = "type"))]
6112#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6113#[repr(u32)]
6114#[doc = "Flags to indicate the status of camera storage."]
6115pub enum StorageStatus {
6116 #[doc = "Storage is missing (no microSD card loaded for example.)"]
6117 STORAGE_STATUS_EMPTY = 0,
6118 #[doc = "Storage present but unformatted."]
6119 STORAGE_STATUS_UNFORMATTED = 1,
6120 #[doc = "Storage present and ready."]
6121 STORAGE_STATUS_READY = 2,
6122 #[doc = "Camera does not supply storage status information. Capacity information in STORAGE_INFORMATION fields will be ignored."]
6123 STORAGE_STATUS_NOT_SUPPORTED = 3,
6124}
6125impl StorageStatus {
6126 pub const DEFAULT: Self = Self::STORAGE_STATUS_EMPTY;
6127}
6128impl Default for StorageStatus {
6129 fn default() -> Self {
6130 Self::DEFAULT
6131 }
6132}
6133#[cfg_attr(feature = "ts", derive(TS))]
6134#[cfg_attr(feature = "ts", ts(export))]
6135#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
6136#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6137#[cfg_attr(feature = "serde", serde(tag = "type"))]
6138#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6139#[repr(u32)]
6140#[doc = "Flags to indicate the type of storage."]
6141pub enum StorageType {
6142 #[doc = "Storage type is not known."]
6143 STORAGE_TYPE_UNKNOWN = 0,
6144 #[doc = "Storage type is USB device."]
6145 STORAGE_TYPE_USB_STICK = 1,
6146 #[doc = "Storage type is SD card."]
6147 STORAGE_TYPE_SD = 2,
6148 #[doc = "Storage type is microSD card."]
6149 STORAGE_TYPE_MICROSD = 3,
6150 #[doc = "Storage type is CFast."]
6151 STORAGE_TYPE_CF = 4,
6152 #[doc = "Storage type is CFexpress."]
6153 STORAGE_TYPE_CFE = 5,
6154 #[doc = "Storage type is XQD."]
6155 STORAGE_TYPE_XQD = 6,
6156 #[doc = "Storage type is HD mass storage type."]
6157 STORAGE_TYPE_HD = 7,
6158 #[doc = "Storage type is other, not listed type."]
6159 STORAGE_TYPE_OTHER = 254,
6160}
6161impl StorageType {
6162 pub const DEFAULT: Self = Self::STORAGE_TYPE_UNKNOWN;
6163}
6164impl Default for StorageType {
6165 fn default() -> Self {
6166 Self::DEFAULT
6167 }
6168}
6169bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags to indicate usage for a particular storage (see STORAGE_INFORMATION.storage_usage and MAV_CMD_SET_STORAGE_USAGE)."] pub struct StorageUsageFlag : u8 { # [doc = "Always set to 1 (indicates STORAGE_INFORMATION.storage_usage is supported)."] const STORAGE_USAGE_FLAG_SET = 1 ; # [doc = "Storage for saving photos."] const STORAGE_USAGE_FLAG_PHOTO = 2 ; # [doc = "Storage for saving videos."] const STORAGE_USAGE_FLAG_VIDEO = 4 ; # [doc = "Storage for saving logs."] const STORAGE_USAGE_FLAG_LOGS = 8 ; } }
6170impl StorageUsageFlag {
6171 pub const DEFAULT: Self = Self::STORAGE_USAGE_FLAG_SET;
6172}
6173impl Default for StorageUsageFlag {
6174 fn default() -> Self {
6175 Self::DEFAULT
6176 }
6177}
6178#[cfg_attr(feature = "ts", derive(TS))]
6179#[cfg_attr(feature = "ts", ts(export))]
6180#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
6181#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6182#[cfg_attr(feature = "serde", serde(tag = "type"))]
6183#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6184#[repr(u32)]
6185#[doc = "Tune formats (used for vehicle buzzer/tone generation)."]
6186pub enum TuneFormat {
6187 #[doc = "Format is QBasic 1.1 Play: <https://www.qbasic.net/en/reference/qb11/Statement/PLAY-006.htm>."]
6188 TUNE_FORMAT_QBASIC1_1 = 1,
6189 #[doc = "Format is Modern Music Markup Language (MML): <https://en.wikipedia.org/wiki/Music_Macro_Language#Modern_MML>."]
6190 TUNE_FORMAT_MML_MODERN = 2,
6191}
6192impl TuneFormat {
6193 pub const DEFAULT: Self = Self::TUNE_FORMAT_QBASIC1_1;
6194}
6195impl Default for TuneFormat {
6196 fn default() -> Self {
6197 Self::DEFAULT
6198 }
6199}
6200#[cfg_attr(feature = "ts", derive(TS))]
6201#[cfg_attr(feature = "ts", ts(export))]
6202#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
6203#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6204#[cfg_attr(feature = "serde", serde(tag = "type"))]
6205#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6206#[repr(u32)]
6207#[doc = "Generalized UAVCAN node health"]
6208pub enum UavcanNodeHealth {
6209 #[doc = "The node is functioning properly."]
6210 UAVCAN_NODE_HEALTH_OK = 0,
6211 #[doc = "A critical parameter went out of range or the node has encountered a minor failure."]
6212 UAVCAN_NODE_HEALTH_WARNING = 1,
6213 #[doc = "The node has encountered a major failure."]
6214 UAVCAN_NODE_HEALTH_ERROR = 2,
6215 #[doc = "The node has suffered a fatal malfunction."]
6216 UAVCAN_NODE_HEALTH_CRITICAL = 3,
6217}
6218impl UavcanNodeHealth {
6219 pub const DEFAULT: Self = Self::UAVCAN_NODE_HEALTH_OK;
6220}
6221impl Default for UavcanNodeHealth {
6222 fn default() -> Self {
6223 Self::DEFAULT
6224 }
6225}
6226#[cfg_attr(feature = "ts", derive(TS))]
6227#[cfg_attr(feature = "ts", ts(export))]
6228#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
6229#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6230#[cfg_attr(feature = "serde", serde(tag = "type"))]
6231#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6232#[repr(u32)]
6233#[doc = "Generalized UAVCAN node mode"]
6234pub enum UavcanNodeMode {
6235 #[doc = "The node is performing its primary functions."]
6236 UAVCAN_NODE_MODE_OPERATIONAL = 0,
6237 #[doc = "The node is initializing; this mode is entered immediately after startup."]
6238 UAVCAN_NODE_MODE_INITIALIZATION = 1,
6239 #[doc = "The node is under maintenance."]
6240 UAVCAN_NODE_MODE_MAINTENANCE = 2,
6241 #[doc = "The node is in the process of updating its software."]
6242 UAVCAN_NODE_MODE_SOFTWARE_UPDATE = 3,
6243 #[doc = "The node is no longer available online."]
6244 UAVCAN_NODE_MODE_OFFLINE = 7,
6245}
6246impl UavcanNodeMode {
6247 pub const DEFAULT: Self = Self::UAVCAN_NODE_MODE_OPERATIONAL;
6248}
6249impl Default for UavcanNodeMode {
6250 fn default() -> Self {
6251 Self::DEFAULT
6252 }
6253}
6254bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags for the global position report."] pub struct UtmDataAvailFlags : u8 { # [doc = "The field time contains valid data."] const UTM_DATA_AVAIL_FLAGS_TIME_VALID = 1 ; # [doc = "The field uas_id contains valid data."] const UTM_DATA_AVAIL_FLAGS_UAS_ID_AVAILABLE = 2 ; # [doc = "The fields lat, lon and h_acc contain valid data."] const UTM_DATA_AVAIL_FLAGS_POSITION_AVAILABLE = 4 ; # [doc = "The fields alt and v_acc contain valid data."] const UTM_DATA_AVAIL_FLAGS_ALTITUDE_AVAILABLE = 8 ; # [doc = "The field relative_alt contains valid data."] const UTM_DATA_AVAIL_FLAGS_RELATIVE_ALTITUDE_AVAILABLE = 16 ; # [doc = "The fields vx and vy contain valid data."] const UTM_DATA_AVAIL_FLAGS_HORIZONTAL_VELO_AVAILABLE = 32 ; # [doc = "The field vz contains valid data."] const UTM_DATA_AVAIL_FLAGS_VERTICAL_VELO_AVAILABLE = 64 ; # [doc = "The fields next_lat, next_lon and next_alt contain valid data."] const UTM_DATA_AVAIL_FLAGS_NEXT_WAYPOINT_AVAILABLE = 128 ; } }
6255impl UtmDataAvailFlags {
6256 pub const DEFAULT: Self = Self::UTM_DATA_AVAIL_FLAGS_TIME_VALID;
6257}
6258impl Default for UtmDataAvailFlags {
6259 fn default() -> Self {
6260 Self::DEFAULT
6261 }
6262}
6263#[cfg_attr(feature = "ts", derive(TS))]
6264#[cfg_attr(feature = "ts", ts(export))]
6265#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
6266#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6267#[cfg_attr(feature = "serde", serde(tag = "type"))]
6268#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6269#[repr(u32)]
6270#[doc = "Airborne status of UAS."]
6271pub enum UtmFlightState {
6272 #[doc = "The flight state can't be determined."]
6273 UTM_FLIGHT_STATE_UNKNOWN = 1,
6274 #[doc = "UAS on ground."]
6275 UTM_FLIGHT_STATE_GROUND = 2,
6276 #[doc = "UAS airborne."]
6277 UTM_FLIGHT_STATE_AIRBORNE = 3,
6278 #[doc = "UAS is in an emergency flight state."]
6279 UTM_FLIGHT_STATE_EMERGENCY = 16,
6280 #[doc = "UAS has no active controls."]
6281 UTM_FLIGHT_STATE_NOCTRL = 32,
6282}
6283impl UtmFlightState {
6284 pub const DEFAULT: Self = Self::UTM_FLIGHT_STATE_UNKNOWN;
6285}
6286impl Default for UtmFlightState {
6287 fn default() -> Self {
6288 Self::DEFAULT
6289 }
6290}
6291#[cfg_attr(feature = "ts", derive(TS))]
6292#[cfg_attr(feature = "ts", ts(export))]
6293#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
6294#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6295#[cfg_attr(feature = "serde", serde(tag = "type"))]
6296#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6297#[repr(u32)]
6298#[doc = "Video stream encodings"]
6299pub enum VideoStreamEncoding {
6300 #[doc = "Stream encoding is unknown"]
6301 VIDEO_STREAM_ENCODING_UNKNOWN = 0,
6302 #[doc = "Stream encoding is H.264"]
6303 VIDEO_STREAM_ENCODING_H264 = 1,
6304 #[doc = "Stream encoding is H.265"]
6305 VIDEO_STREAM_ENCODING_H265 = 2,
6306}
6307impl VideoStreamEncoding {
6308 pub const DEFAULT: Self = Self::VIDEO_STREAM_ENCODING_UNKNOWN;
6309}
6310impl Default for VideoStreamEncoding {
6311 fn default() -> Self {
6312 Self::DEFAULT
6313 }
6314}
6315bitflags! { # [cfg_attr (feature = "ts" , derive (TS))] # [cfg_attr (feature = "ts" , ts (export , type = "number"))] # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Stream status flags (Bitmap)"] pub struct VideoStreamStatusFlags : u16 { # [doc = "Stream is active (running)"] const VIDEO_STREAM_STATUS_FLAGS_RUNNING = 1 ; # [doc = "Stream is thermal imaging"] const VIDEO_STREAM_STATUS_FLAGS_THERMAL = 2 ; # [doc = "Stream can report absolute thermal range (see CAMERA_THERMAL_RANGE)."] const VIDEO_STREAM_STATUS_FLAGS_THERMAL_RANGE_ENABLED = 4 ; } }
6316impl VideoStreamStatusFlags {
6317 pub const DEFAULT: Self = Self::VIDEO_STREAM_STATUS_FLAGS_RUNNING;
6318}
6319impl Default for VideoStreamStatusFlags {
6320 fn default() -> Self {
6321 Self::DEFAULT
6322 }
6323}
6324#[cfg_attr(feature = "ts", derive(TS))]
6325#[cfg_attr(feature = "ts", ts(export))]
6326#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
6327#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6328#[cfg_attr(feature = "serde", serde(tag = "type"))]
6329#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6330#[repr(u32)]
6331#[doc = "Video stream types"]
6332pub enum VideoStreamType {
6333 #[doc = "Stream is RTSP"]
6334 VIDEO_STREAM_TYPE_RTSP = 0,
6335 #[doc = "Stream is RTP UDP (URI gives the port number)"]
6336 VIDEO_STREAM_TYPE_RTPUDP = 1,
6337 #[doc = "Stream is MPEG on TCP"]
6338 VIDEO_STREAM_TYPE_TCP_MPEG = 2,
6339 #[doc = "Stream is MPEG TS (URI gives the port number)"]
6340 VIDEO_STREAM_TYPE_MPEG_TS = 3,
6341}
6342impl VideoStreamType {
6343 pub const DEFAULT: Self = Self::VIDEO_STREAM_TYPE_RTSP;
6344}
6345impl Default for VideoStreamType {
6346 fn default() -> Self {
6347 Self::DEFAULT
6348 }
6349}
6350#[cfg_attr(feature = "ts", derive(TS))]
6351#[cfg_attr(feature = "ts", ts(export))]
6352#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
6353#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6354#[cfg_attr(feature = "serde", serde(tag = "type"))]
6355#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6356#[repr(u32)]
6357#[doc = "Direction of VTOL transition"]
6358pub enum VtolTransitionHeading {
6359 #[doc = "Respect the heading configuration of the vehicle."]
6360 VTOL_TRANSITION_HEADING_VEHICLE_DEFAULT = 0,
6361 #[doc = "Use the heading pointing towards the next waypoint."]
6362 VTOL_TRANSITION_HEADING_NEXT_WAYPOINT = 1,
6363 #[doc = "Use the heading on takeoff (while sitting on the ground)."]
6364 VTOL_TRANSITION_HEADING_TAKEOFF = 2,
6365 #[doc = "Use the specified heading in parameter 4."]
6366 VTOL_TRANSITION_HEADING_SPECIFIED = 3,
6367 #[doc = "Use the current heading when reaching takeoff altitude (potentially facing the wind when weather-vaning is active)."]
6368 VTOL_TRANSITION_HEADING_ANY = 4,
6369}
6370impl VtolTransitionHeading {
6371 pub const DEFAULT: Self = Self::VTOL_TRANSITION_HEADING_VEHICLE_DEFAULT;
6372}
6373impl Default for VtolTransitionHeading {
6374 fn default() -> Self {
6375 Self::DEFAULT
6376 }
6377}
6378#[cfg_attr(feature = "ts", derive(TS))]
6379#[cfg_attr(feature = "ts", ts(export))]
6380#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
6381#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6382#[cfg_attr(feature = "serde", serde(tag = "type"))]
6383#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6384#[repr(u32)]
6385#[doc = "WiFi Mode."]
6386pub enum WifiConfigApMode {
6387 #[doc = "WiFi mode is undefined."]
6388 WIFI_CONFIG_AP_MODE_UNDEFINED = 0,
6389 #[doc = "WiFi configured as an access point."]
6390 WIFI_CONFIG_AP_MODE_AP = 1,
6391 #[doc = "WiFi configured as a station connected to an existing local WiFi network."]
6392 WIFI_CONFIG_AP_MODE_STATION = 2,
6393 #[doc = "WiFi disabled."]
6394 WIFI_CONFIG_AP_MODE_DISABLED = 3,
6395}
6396impl WifiConfigApMode {
6397 pub const DEFAULT: Self = Self::WIFI_CONFIG_AP_MODE_UNDEFINED;
6398}
6399impl Default for WifiConfigApMode {
6400 fn default() -> Self {
6401 Self::DEFAULT
6402 }
6403}
6404#[cfg_attr(feature = "ts", derive(TS))]
6405#[cfg_attr(feature = "ts", ts(export))]
6406#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
6407#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6408#[cfg_attr(feature = "serde", serde(tag = "type"))]
6409#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6410#[repr(u32)]
6411#[doc = "Possible responses from a WIFI_CONFIG_AP message."]
6412pub enum WifiConfigApResponse {
6413 #[doc = "Undefined response. Likely an indicative of a system that doesn't support this request."]
6414 WIFI_CONFIG_AP_RESPONSE_UNDEFINED = 0,
6415 #[doc = "Changes accepted."]
6416 WIFI_CONFIG_AP_RESPONSE_ACCEPTED = 1,
6417 #[doc = "Changes rejected."]
6418 WIFI_CONFIG_AP_RESPONSE_REJECTED = 2,
6419 #[doc = "Invalid Mode."]
6420 WIFI_CONFIG_AP_RESPONSE_MODE_ERROR = 3,
6421 #[doc = "Invalid SSID."]
6422 WIFI_CONFIG_AP_RESPONSE_SSID_ERROR = 4,
6423 #[doc = "Invalid Password."]
6424 WIFI_CONFIG_AP_RESPONSE_PASSWORD_ERROR = 5,
6425}
6426impl WifiConfigApResponse {
6427 pub const DEFAULT: Self = Self::WIFI_CONFIG_AP_RESPONSE_UNDEFINED;
6428}
6429impl Default for WifiConfigApResponse {
6430 fn default() -> Self {
6431 Self::DEFAULT
6432 }
6433}
6434#[cfg_attr(feature = "ts", derive(TS))]
6435#[cfg_attr(feature = "ts", ts(export))]
6436#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
6437#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6438#[cfg_attr(feature = "serde", serde(tag = "type"))]
6439#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6440#[repr(u32)]
6441#[doc = "Winch actions."]
6442pub enum WinchActions {
6443 #[doc = "Allow motor to freewheel."]
6444 WINCH_RELAXED = 0,
6445 #[doc = "Wind or unwind specified length of line, optionally using specified rate."]
6446 WINCH_RELATIVE_LENGTH_CONTROL = 1,
6447 #[doc = "Wind or unwind line at specified rate."]
6448 WINCH_RATE_CONTROL = 2,
6449 #[doc = "Perform the locking sequence to relieve motor while in the fully retracted position. Only action and instance command parameters are used, others are ignored."]
6450 WINCH_LOCK = 3,
6451 #[doc = "Sequence of drop, slow down, touch down, reel up, lock. Only action and instance command parameters are used, others are ignored."]
6452 WINCH_DELIVER = 4,
6453 #[doc = "Engage motor and hold current position. Only action and instance command parameters are used, others are ignored."]
6454 WINCH_HOLD = 5,
6455 #[doc = "Return the reel to the fully retracted position. Only action and instance command parameters are used, others are ignored."]
6456 WINCH_RETRACT = 6,
6457 #[doc = "Load the reel with line. The winch will calculate the total loaded length and stop when the tension exceeds a threshold. Only action and instance command parameters are used, others are ignored."]
6458 WINCH_LOAD_LINE = 7,
6459 #[doc = "Spool out the entire length of the line. Only action and instance command parameters are used, others are ignored."]
6460 WINCH_ABANDON_LINE = 8,
6461 #[doc = "Spools out just enough to present the hook to the user to load the payload. Only action and instance command parameters are used, others are ignored"]
6462 WINCH_LOAD_PAYLOAD = 9,
6463}
6464impl WinchActions {
6465 pub const DEFAULT: Self = Self::WINCH_RELAXED;
6466}
6467impl Default for WinchActions {
6468 fn default() -> Self {
6469 Self::DEFAULT
6470 }
6471}
6472#[doc = "Set the vehicle attitude and body angular rates."]
6473#[doc = ""]
6474#[doc = "ID: 140"]
6475#[derive(Debug, Clone, PartialEq)]
6476#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6477#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6478#[cfg_attr(feature = "ts", derive(TS))]
6479#[cfg_attr(feature = "ts", ts(export))]
6480pub struct ACTUATOR_CONTROL_TARGET_DATA {
6481 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
6482 pub time_usec: u64,
6483 #[doc = "Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs."]
6484 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6485 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
6486 pub controls: [f32; 8],
6487 #[doc = "Actuator group. The \"_mlx\" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances."]
6488 pub group_mlx: u8,
6489}
6490impl ACTUATOR_CONTROL_TARGET_DATA {
6491 pub const ENCODED_LEN: usize = 41usize;
6492 pub const DEFAULT: Self = Self {
6493 time_usec: 0_u64,
6494 controls: [0.0_f32; 8usize],
6495 group_mlx: 0_u8,
6496 };
6497 #[cfg(feature = "arbitrary")]
6498 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6499 use arbitrary::{Arbitrary, Unstructured};
6500 let mut buf = [0u8; 1024];
6501 rng.fill_bytes(&mut buf);
6502 let mut unstructured = Unstructured::new(&buf);
6503 Self::arbitrary(&mut unstructured).unwrap_or_default()
6504 }
6505}
6506impl Default for ACTUATOR_CONTROL_TARGET_DATA {
6507 fn default() -> Self {
6508 Self::DEFAULT.clone()
6509 }
6510}
6511impl MessageData for ACTUATOR_CONTROL_TARGET_DATA {
6512 type Message = MavMessage;
6513 const ID: u32 = 140u32;
6514 const NAME: &'static str = "ACTUATOR_CONTROL_TARGET";
6515 const EXTRA_CRC: u8 = 181u8;
6516 const ENCODED_LEN: usize = 41usize;
6517 fn deser(
6518 _version: MavlinkVersion,
6519 __input: &[u8],
6520 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6521 let avail_len = __input.len();
6522 let mut payload_buf = [0; Self::ENCODED_LEN];
6523 let mut buf = if avail_len < Self::ENCODED_LEN {
6524 payload_buf[0..avail_len].copy_from_slice(__input);
6525 Bytes::new(&payload_buf)
6526 } else {
6527 Bytes::new(__input)
6528 };
6529 let mut __struct = Self::default();
6530 __struct.time_usec = buf.get_u64_le()?;
6531 for v in &mut __struct.controls {
6532 let val = buf.get_f32_le()?;
6533 *v = val;
6534 }
6535 __struct.group_mlx = buf.get_u8()?;
6536 Ok(__struct)
6537 }
6538 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6539 let mut __tmp = BytesMut::new(bytes);
6540 #[allow(clippy::absurd_extreme_comparisons)]
6541 #[allow(unused_comparisons)]
6542 if __tmp.remaining() < Self::ENCODED_LEN {
6543 panic!(
6544 "buffer is too small (need {} bytes, but got {})",
6545 Self::ENCODED_LEN,
6546 __tmp.remaining(),
6547 )
6548 }
6549 __tmp.put_u64_le(self.time_usec);
6550 for val in &self.controls {
6551 __tmp.put_f32_le(*val);
6552 }
6553 __tmp.put_u8(self.group_mlx);
6554 if matches!(version, MavlinkVersion::V2) {
6555 let len = __tmp.len();
6556 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6557 } else {
6558 __tmp.len()
6559 }
6560 }
6561}
6562#[doc = "The raw values of the actuator outputs (e.g. on Pixhawk, from MAIN, AUX ports). This message supersedes SERVO_OUTPUT_RAW."]
6563#[doc = ""]
6564#[doc = "ID: 375"]
6565#[derive(Debug, Clone, PartialEq)]
6566#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6567#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6568#[cfg_attr(feature = "ts", derive(TS))]
6569#[cfg_attr(feature = "ts", ts(export))]
6570pub struct ACTUATOR_OUTPUT_STATUS_DATA {
6571 #[doc = "Timestamp (since system boot)."]
6572 pub time_usec: u64,
6573 #[doc = "Active outputs"]
6574 pub active: u32,
6575 #[doc = "Servo / motor output array values. Zero values indicate unused channels."]
6576 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6577 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
6578 pub actuator: [f32; 32],
6579}
6580impl ACTUATOR_OUTPUT_STATUS_DATA {
6581 pub const ENCODED_LEN: usize = 140usize;
6582 pub const DEFAULT: Self = Self {
6583 time_usec: 0_u64,
6584 active: 0_u32,
6585 actuator: [0.0_f32; 32usize],
6586 };
6587 #[cfg(feature = "arbitrary")]
6588 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6589 use arbitrary::{Arbitrary, Unstructured};
6590 let mut buf = [0u8; 1024];
6591 rng.fill_bytes(&mut buf);
6592 let mut unstructured = Unstructured::new(&buf);
6593 Self::arbitrary(&mut unstructured).unwrap_or_default()
6594 }
6595}
6596impl Default for ACTUATOR_OUTPUT_STATUS_DATA {
6597 fn default() -> Self {
6598 Self::DEFAULT.clone()
6599 }
6600}
6601impl MessageData for ACTUATOR_OUTPUT_STATUS_DATA {
6602 type Message = MavMessage;
6603 const ID: u32 = 375u32;
6604 const NAME: &'static str = "ACTUATOR_OUTPUT_STATUS";
6605 const EXTRA_CRC: u8 = 251u8;
6606 const ENCODED_LEN: usize = 140usize;
6607 fn deser(
6608 _version: MavlinkVersion,
6609 __input: &[u8],
6610 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6611 let avail_len = __input.len();
6612 let mut payload_buf = [0; Self::ENCODED_LEN];
6613 let mut buf = if avail_len < Self::ENCODED_LEN {
6614 payload_buf[0..avail_len].copy_from_slice(__input);
6615 Bytes::new(&payload_buf)
6616 } else {
6617 Bytes::new(__input)
6618 };
6619 let mut __struct = Self::default();
6620 __struct.time_usec = buf.get_u64_le()?;
6621 __struct.active = buf.get_u32_le()?;
6622 for v in &mut __struct.actuator {
6623 let val = buf.get_f32_le()?;
6624 *v = val;
6625 }
6626 Ok(__struct)
6627 }
6628 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6629 let mut __tmp = BytesMut::new(bytes);
6630 #[allow(clippy::absurd_extreme_comparisons)]
6631 #[allow(unused_comparisons)]
6632 if __tmp.remaining() < Self::ENCODED_LEN {
6633 panic!(
6634 "buffer is too small (need {} bytes, but got {})",
6635 Self::ENCODED_LEN,
6636 __tmp.remaining(),
6637 )
6638 }
6639 __tmp.put_u64_le(self.time_usec);
6640 __tmp.put_u32_le(self.active);
6641 for val in &self.actuator {
6642 __tmp.put_f32_le(*val);
6643 }
6644 if matches!(version, MavlinkVersion::V2) {
6645 let len = __tmp.len();
6646 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6647 } else {
6648 __tmp.len()
6649 }
6650 }
6651}
6652#[doc = "The location and information of an ADSB vehicle."]
6653#[doc = ""]
6654#[doc = "ID: 246"]
6655#[derive(Debug, Clone, PartialEq)]
6656#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6657#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6658#[cfg_attr(feature = "ts", derive(TS))]
6659#[cfg_attr(feature = "ts", ts(export))]
6660pub struct ADSB_VEHICLE_DATA {
6661 #[doc = "ICAO address"]
6662 pub ICAO_address: u32,
6663 #[doc = "Latitude"]
6664 pub lat: i32,
6665 #[doc = "Longitude"]
6666 pub lon: i32,
6667 #[doc = "Altitude(ASL)"]
6668 pub altitude: i32,
6669 #[doc = "Course over ground"]
6670 pub heading: u16,
6671 #[doc = "The horizontal velocity"]
6672 pub hor_velocity: u16,
6673 #[doc = "The vertical velocity. Positive is up"]
6674 pub ver_velocity: i16,
6675 #[doc = "Bitmap to indicate various statuses including valid data fields"]
6676 pub flags: AdsbFlags,
6677 #[doc = "Squawk code. Note that the code is in decimal: e.g. 7700 (general emergency) is encoded as binary 0b0001_1110_0001_0100, not(!) as 0b0000_111_111_000_000"]
6678 pub squawk: u16,
6679 #[doc = "ADSB altitude type."]
6680 pub altitude_type: AdsbAltitudeType,
6681 #[doc = "The callsign, 8+null"]
6682 #[cfg_attr(feature = "ts", ts(type = "string"))]
6683 pub callsign: CharArray<9>,
6684 #[doc = "ADSB emitter type."]
6685 pub emitter_type: AdsbEmitterType,
6686 #[doc = "Time since last communication in seconds"]
6687 pub tslc: u8,
6688}
6689impl ADSB_VEHICLE_DATA {
6690 pub const ENCODED_LEN: usize = 38usize;
6691 pub const DEFAULT: Self = Self {
6692 ICAO_address: 0_u32,
6693 lat: 0_i32,
6694 lon: 0_i32,
6695 altitude: 0_i32,
6696 heading: 0_u16,
6697 hor_velocity: 0_u16,
6698 ver_velocity: 0_i16,
6699 flags: AdsbFlags::DEFAULT,
6700 squawk: 0_u16,
6701 altitude_type: AdsbAltitudeType::DEFAULT,
6702 callsign: CharArray::new([0_u8; 9usize]),
6703 emitter_type: AdsbEmitterType::DEFAULT,
6704 tslc: 0_u8,
6705 };
6706 #[cfg(feature = "arbitrary")]
6707 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6708 use arbitrary::{Arbitrary, Unstructured};
6709 let mut buf = [0u8; 1024];
6710 rng.fill_bytes(&mut buf);
6711 let mut unstructured = Unstructured::new(&buf);
6712 Self::arbitrary(&mut unstructured).unwrap_or_default()
6713 }
6714}
6715impl Default for ADSB_VEHICLE_DATA {
6716 fn default() -> Self {
6717 Self::DEFAULT.clone()
6718 }
6719}
6720impl MessageData for ADSB_VEHICLE_DATA {
6721 type Message = MavMessage;
6722 const ID: u32 = 246u32;
6723 const NAME: &'static str = "ADSB_VEHICLE";
6724 const EXTRA_CRC: u8 = 184u8;
6725 const ENCODED_LEN: usize = 38usize;
6726 fn deser(
6727 _version: MavlinkVersion,
6728 __input: &[u8],
6729 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6730 let avail_len = __input.len();
6731 let mut payload_buf = [0; Self::ENCODED_LEN];
6732 let mut buf = if avail_len < Self::ENCODED_LEN {
6733 payload_buf[0..avail_len].copy_from_slice(__input);
6734 Bytes::new(&payload_buf)
6735 } else {
6736 Bytes::new(__input)
6737 };
6738 let mut __struct = Self::default();
6739 __struct.ICAO_address = buf.get_u32_le()?;
6740 __struct.lat = buf.get_i32_le()?;
6741 __struct.lon = buf.get_i32_le()?;
6742 __struct.altitude = buf.get_i32_le()?;
6743 __struct.heading = buf.get_u16_le()?;
6744 __struct.hor_velocity = buf.get_u16_le()?;
6745 __struct.ver_velocity = buf.get_i16_le()?;
6746 let tmp = buf.get_u16_le()?;
6747 __struct.flags = AdsbFlags::from_bits(tmp as <AdsbFlags as Flags>::Bits).ok_or(
6748 ::mavlink_core::error::ParserError::InvalidFlag {
6749 flag_type: "AdsbFlags",
6750 value: tmp as u64,
6751 },
6752 )?;
6753 __struct.squawk = buf.get_u16_le()?;
6754 let tmp = buf.get_u8()?;
6755 __struct.altitude_type =
6756 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6757 enum_type: "AdsbAltitudeType",
6758 value: tmp as u64,
6759 })?;
6760 let mut tmp = [0_u8; 9usize];
6761 for v in &mut tmp {
6762 *v = buf.get_u8()?;
6763 }
6764 __struct.callsign = CharArray::new(tmp);
6765 let tmp = buf.get_u8()?;
6766 __struct.emitter_type =
6767 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6768 enum_type: "AdsbEmitterType",
6769 value: tmp as u64,
6770 })?;
6771 __struct.tslc = buf.get_u8()?;
6772 Ok(__struct)
6773 }
6774 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6775 let mut __tmp = BytesMut::new(bytes);
6776 #[allow(clippy::absurd_extreme_comparisons)]
6777 #[allow(unused_comparisons)]
6778 if __tmp.remaining() < Self::ENCODED_LEN {
6779 panic!(
6780 "buffer is too small (need {} bytes, but got {})",
6781 Self::ENCODED_LEN,
6782 __tmp.remaining(),
6783 )
6784 }
6785 __tmp.put_u32_le(self.ICAO_address);
6786 __tmp.put_i32_le(self.lat);
6787 __tmp.put_i32_le(self.lon);
6788 __tmp.put_i32_le(self.altitude);
6789 __tmp.put_u16_le(self.heading);
6790 __tmp.put_u16_le(self.hor_velocity);
6791 __tmp.put_i16_le(self.ver_velocity);
6792 __tmp.put_u16_le(self.flags.bits() as u16);
6793 __tmp.put_u16_le(self.squawk);
6794 __tmp.put_u8(self.altitude_type as u8);
6795 for val in &self.callsign {
6796 __tmp.put_u8(*val);
6797 }
6798 __tmp.put_u8(self.emitter_type as u8);
6799 __tmp.put_u8(self.tslc);
6800 if matches!(version, MavlinkVersion::V2) {
6801 let len = __tmp.len();
6802 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6803 } else {
6804 __tmp.len()
6805 }
6806 }
6807}
6808#[doc = "The location and information of an AIS vessel."]
6809#[doc = ""]
6810#[doc = "ID: 301"]
6811#[derive(Debug, Clone, PartialEq)]
6812#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6813#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6814#[cfg_attr(feature = "ts", derive(TS))]
6815#[cfg_attr(feature = "ts", ts(export))]
6816pub struct AIS_VESSEL_DATA {
6817 #[doc = "Mobile Marine Service Identifier, 9 decimal digits"]
6818 pub MMSI: u32,
6819 #[doc = "Latitude"]
6820 pub lat: i32,
6821 #[doc = "Longitude"]
6822 pub lon: i32,
6823 #[doc = "Course over ground"]
6824 pub COG: u16,
6825 #[doc = "True heading"]
6826 pub heading: u16,
6827 #[doc = "Speed over ground"]
6828 pub velocity: u16,
6829 #[doc = "Distance from lat/lon location to bow"]
6830 pub dimension_bow: u16,
6831 #[doc = "Distance from lat/lon location to stern"]
6832 pub dimension_stern: u16,
6833 #[doc = "Time since last communication in seconds"]
6834 pub tslc: u16,
6835 #[doc = "Bitmask to indicate various statuses including valid data fields"]
6836 pub flags: AisFlags,
6837 #[doc = "Turn rate"]
6838 pub turn_rate: i8,
6839 #[doc = "Navigational status"]
6840 pub navigational_status: AisNavStatus,
6841 #[doc = "Type of vessels"]
6842 pub mavtype: AisType,
6843 #[doc = "Distance from lat/lon location to port side"]
6844 pub dimension_port: u8,
6845 #[doc = "Distance from lat/lon location to starboard side"]
6846 pub dimension_starboard: u8,
6847 #[doc = "The vessel callsign"]
6848 #[cfg_attr(feature = "ts", ts(type = "string"))]
6849 pub callsign: CharArray<7>,
6850 #[doc = "The vessel name"]
6851 #[cfg_attr(feature = "ts", ts(type = "string"))]
6852 pub name: CharArray<20>,
6853}
6854impl AIS_VESSEL_DATA {
6855 pub const ENCODED_LEN: usize = 58usize;
6856 pub const DEFAULT: Self = Self {
6857 MMSI: 0_u32,
6858 lat: 0_i32,
6859 lon: 0_i32,
6860 COG: 0_u16,
6861 heading: 0_u16,
6862 velocity: 0_u16,
6863 dimension_bow: 0_u16,
6864 dimension_stern: 0_u16,
6865 tslc: 0_u16,
6866 flags: AisFlags::DEFAULT,
6867 turn_rate: 0_i8,
6868 navigational_status: AisNavStatus::DEFAULT,
6869 mavtype: AisType::DEFAULT,
6870 dimension_port: 0_u8,
6871 dimension_starboard: 0_u8,
6872 callsign: CharArray::new([0_u8; 7usize]),
6873 name: CharArray::new([0_u8; 20usize]),
6874 };
6875 #[cfg(feature = "arbitrary")]
6876 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6877 use arbitrary::{Arbitrary, Unstructured};
6878 let mut buf = [0u8; 1024];
6879 rng.fill_bytes(&mut buf);
6880 let mut unstructured = Unstructured::new(&buf);
6881 Self::arbitrary(&mut unstructured).unwrap_or_default()
6882 }
6883}
6884impl Default for AIS_VESSEL_DATA {
6885 fn default() -> Self {
6886 Self::DEFAULT.clone()
6887 }
6888}
6889impl MessageData for AIS_VESSEL_DATA {
6890 type Message = MavMessage;
6891 const ID: u32 = 301u32;
6892 const NAME: &'static str = "AIS_VESSEL";
6893 const EXTRA_CRC: u8 = 243u8;
6894 const ENCODED_LEN: usize = 58usize;
6895 fn deser(
6896 _version: MavlinkVersion,
6897 __input: &[u8],
6898 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6899 let avail_len = __input.len();
6900 let mut payload_buf = [0; Self::ENCODED_LEN];
6901 let mut buf = if avail_len < Self::ENCODED_LEN {
6902 payload_buf[0..avail_len].copy_from_slice(__input);
6903 Bytes::new(&payload_buf)
6904 } else {
6905 Bytes::new(__input)
6906 };
6907 let mut __struct = Self::default();
6908 __struct.MMSI = buf.get_u32_le()?;
6909 __struct.lat = buf.get_i32_le()?;
6910 __struct.lon = buf.get_i32_le()?;
6911 __struct.COG = buf.get_u16_le()?;
6912 __struct.heading = buf.get_u16_le()?;
6913 __struct.velocity = buf.get_u16_le()?;
6914 __struct.dimension_bow = buf.get_u16_le()?;
6915 __struct.dimension_stern = buf.get_u16_le()?;
6916 __struct.tslc = buf.get_u16_le()?;
6917 let tmp = buf.get_u16_le()?;
6918 __struct.flags = AisFlags::from_bits(tmp as <AisFlags as Flags>::Bits).ok_or(
6919 ::mavlink_core::error::ParserError::InvalidFlag {
6920 flag_type: "AisFlags",
6921 value: tmp as u64,
6922 },
6923 )?;
6924 __struct.turn_rate = buf.get_i8()?;
6925 let tmp = buf.get_u8()?;
6926 __struct.navigational_status =
6927 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6928 enum_type: "AisNavStatus",
6929 value: tmp as u64,
6930 })?;
6931 let tmp = buf.get_u8()?;
6932 __struct.mavtype =
6933 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6934 enum_type: "AisType",
6935 value: tmp as u64,
6936 })?;
6937 __struct.dimension_port = buf.get_u8()?;
6938 __struct.dimension_starboard = buf.get_u8()?;
6939 let mut tmp = [0_u8; 7usize];
6940 for v in &mut tmp {
6941 *v = buf.get_u8()?;
6942 }
6943 __struct.callsign = CharArray::new(tmp);
6944 let mut tmp = [0_u8; 20usize];
6945 for v in &mut tmp {
6946 *v = buf.get_u8()?;
6947 }
6948 __struct.name = CharArray::new(tmp);
6949 Ok(__struct)
6950 }
6951 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6952 let mut __tmp = BytesMut::new(bytes);
6953 #[allow(clippy::absurd_extreme_comparisons)]
6954 #[allow(unused_comparisons)]
6955 if __tmp.remaining() < Self::ENCODED_LEN {
6956 panic!(
6957 "buffer is too small (need {} bytes, but got {})",
6958 Self::ENCODED_LEN,
6959 __tmp.remaining(),
6960 )
6961 }
6962 __tmp.put_u32_le(self.MMSI);
6963 __tmp.put_i32_le(self.lat);
6964 __tmp.put_i32_le(self.lon);
6965 __tmp.put_u16_le(self.COG);
6966 __tmp.put_u16_le(self.heading);
6967 __tmp.put_u16_le(self.velocity);
6968 __tmp.put_u16_le(self.dimension_bow);
6969 __tmp.put_u16_le(self.dimension_stern);
6970 __tmp.put_u16_le(self.tslc);
6971 __tmp.put_u16_le(self.flags.bits() as u16);
6972 __tmp.put_i8(self.turn_rate);
6973 __tmp.put_u8(self.navigational_status as u8);
6974 __tmp.put_u8(self.mavtype as u8);
6975 __tmp.put_u8(self.dimension_port);
6976 __tmp.put_u8(self.dimension_starboard);
6977 for val in &self.callsign {
6978 __tmp.put_u8(*val);
6979 }
6980 for val in &self.name {
6981 __tmp.put_u8(*val);
6982 }
6983 if matches!(version, MavlinkVersion::V2) {
6984 let len = __tmp.len();
6985 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6986 } else {
6987 __tmp.len()
6988 }
6989 }
6990}
6991#[doc = "The current system altitude."]
6992#[doc = ""]
6993#[doc = "ID: 141"]
6994#[derive(Debug, Clone, PartialEq)]
6995#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6996#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6997#[cfg_attr(feature = "ts", derive(TS))]
6998#[cfg_attr(feature = "ts", ts(export))]
6999pub struct ALTITUDE_DATA {
7000 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
7001 pub time_usec: u64,
7002 #[doc = "This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights."]
7003 pub altitude_monotonic: f32,
7004 #[doc = "This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude."]
7005 pub altitude_amsl: f32,
7006 #[doc = "This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive."]
7007 pub altitude_local: f32,
7008 #[doc = "This is the altitude above the home position. It resets on each change of the current home position."]
7009 pub altitude_relative: f32,
7010 #[doc = "This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown."]
7011 pub altitude_terrain: f32,
7012 #[doc = "This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available."]
7013 pub bottom_clearance: f32,
7014}
7015impl ALTITUDE_DATA {
7016 pub const ENCODED_LEN: usize = 32usize;
7017 pub const DEFAULT: Self = Self {
7018 time_usec: 0_u64,
7019 altitude_monotonic: 0.0_f32,
7020 altitude_amsl: 0.0_f32,
7021 altitude_local: 0.0_f32,
7022 altitude_relative: 0.0_f32,
7023 altitude_terrain: 0.0_f32,
7024 bottom_clearance: 0.0_f32,
7025 };
7026 #[cfg(feature = "arbitrary")]
7027 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7028 use arbitrary::{Arbitrary, Unstructured};
7029 let mut buf = [0u8; 1024];
7030 rng.fill_bytes(&mut buf);
7031 let mut unstructured = Unstructured::new(&buf);
7032 Self::arbitrary(&mut unstructured).unwrap_or_default()
7033 }
7034}
7035impl Default for ALTITUDE_DATA {
7036 fn default() -> Self {
7037 Self::DEFAULT.clone()
7038 }
7039}
7040impl MessageData for ALTITUDE_DATA {
7041 type Message = MavMessage;
7042 const ID: u32 = 141u32;
7043 const NAME: &'static str = "ALTITUDE";
7044 const EXTRA_CRC: u8 = 47u8;
7045 const ENCODED_LEN: usize = 32usize;
7046 fn deser(
7047 _version: MavlinkVersion,
7048 __input: &[u8],
7049 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7050 let avail_len = __input.len();
7051 let mut payload_buf = [0; Self::ENCODED_LEN];
7052 let mut buf = if avail_len < Self::ENCODED_LEN {
7053 payload_buf[0..avail_len].copy_from_slice(__input);
7054 Bytes::new(&payload_buf)
7055 } else {
7056 Bytes::new(__input)
7057 };
7058 let mut __struct = Self::default();
7059 __struct.time_usec = buf.get_u64_le()?;
7060 __struct.altitude_monotonic = buf.get_f32_le()?;
7061 __struct.altitude_amsl = buf.get_f32_le()?;
7062 __struct.altitude_local = buf.get_f32_le()?;
7063 __struct.altitude_relative = buf.get_f32_le()?;
7064 __struct.altitude_terrain = buf.get_f32_le()?;
7065 __struct.bottom_clearance = buf.get_f32_le()?;
7066 Ok(__struct)
7067 }
7068 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7069 let mut __tmp = BytesMut::new(bytes);
7070 #[allow(clippy::absurd_extreme_comparisons)]
7071 #[allow(unused_comparisons)]
7072 if __tmp.remaining() < Self::ENCODED_LEN {
7073 panic!(
7074 "buffer is too small (need {} bytes, but got {})",
7075 Self::ENCODED_LEN,
7076 __tmp.remaining(),
7077 )
7078 }
7079 __tmp.put_u64_le(self.time_usec);
7080 __tmp.put_f32_le(self.altitude_monotonic);
7081 __tmp.put_f32_le(self.altitude_amsl);
7082 __tmp.put_f32_le(self.altitude_local);
7083 __tmp.put_f32_le(self.altitude_relative);
7084 __tmp.put_f32_le(self.altitude_terrain);
7085 __tmp.put_f32_le(self.bottom_clearance);
7086 if matches!(version, MavlinkVersion::V2) {
7087 let len = __tmp.len();
7088 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7089 } else {
7090 __tmp.len()
7091 }
7092 }
7093}
7094#[doc = "The attitude in the aeronautical frame (right-handed, Z-down, Y-right, X-front, ZYX, intrinsic)."]
7095#[doc = ""]
7096#[doc = "ID: 30"]
7097#[derive(Debug, Clone, PartialEq)]
7098#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7099#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7100#[cfg_attr(feature = "ts", derive(TS))]
7101#[cfg_attr(feature = "ts", ts(export))]
7102pub struct ATTITUDE_DATA {
7103 #[doc = "Timestamp (time since system boot)."]
7104 pub time_boot_ms: u32,
7105 #[doc = "Roll angle (-pi..+pi)"]
7106 pub roll: f32,
7107 #[doc = "Pitch angle (-pi..+pi)"]
7108 pub pitch: f32,
7109 #[doc = "Yaw angle (-pi..+pi)"]
7110 pub yaw: f32,
7111 #[doc = "Roll angular speed"]
7112 pub rollspeed: f32,
7113 #[doc = "Pitch angular speed"]
7114 pub pitchspeed: f32,
7115 #[doc = "Yaw angular speed"]
7116 pub yawspeed: f32,
7117}
7118impl ATTITUDE_DATA {
7119 pub const ENCODED_LEN: usize = 28usize;
7120 pub const DEFAULT: Self = Self {
7121 time_boot_ms: 0_u32,
7122 roll: 0.0_f32,
7123 pitch: 0.0_f32,
7124 yaw: 0.0_f32,
7125 rollspeed: 0.0_f32,
7126 pitchspeed: 0.0_f32,
7127 yawspeed: 0.0_f32,
7128 };
7129 #[cfg(feature = "arbitrary")]
7130 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7131 use arbitrary::{Arbitrary, Unstructured};
7132 let mut buf = [0u8; 1024];
7133 rng.fill_bytes(&mut buf);
7134 let mut unstructured = Unstructured::new(&buf);
7135 Self::arbitrary(&mut unstructured).unwrap_or_default()
7136 }
7137}
7138impl Default for ATTITUDE_DATA {
7139 fn default() -> Self {
7140 Self::DEFAULT.clone()
7141 }
7142}
7143impl MessageData for ATTITUDE_DATA {
7144 type Message = MavMessage;
7145 const ID: u32 = 30u32;
7146 const NAME: &'static str = "ATTITUDE";
7147 const EXTRA_CRC: u8 = 39u8;
7148 const ENCODED_LEN: usize = 28usize;
7149 fn deser(
7150 _version: MavlinkVersion,
7151 __input: &[u8],
7152 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7153 let avail_len = __input.len();
7154 let mut payload_buf = [0; Self::ENCODED_LEN];
7155 let mut buf = if avail_len < Self::ENCODED_LEN {
7156 payload_buf[0..avail_len].copy_from_slice(__input);
7157 Bytes::new(&payload_buf)
7158 } else {
7159 Bytes::new(__input)
7160 };
7161 let mut __struct = Self::default();
7162 __struct.time_boot_ms = buf.get_u32_le()?;
7163 __struct.roll = buf.get_f32_le()?;
7164 __struct.pitch = buf.get_f32_le()?;
7165 __struct.yaw = buf.get_f32_le()?;
7166 __struct.rollspeed = buf.get_f32_le()?;
7167 __struct.pitchspeed = buf.get_f32_le()?;
7168 __struct.yawspeed = buf.get_f32_le()?;
7169 Ok(__struct)
7170 }
7171 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7172 let mut __tmp = BytesMut::new(bytes);
7173 #[allow(clippy::absurd_extreme_comparisons)]
7174 #[allow(unused_comparisons)]
7175 if __tmp.remaining() < Self::ENCODED_LEN {
7176 panic!(
7177 "buffer is too small (need {} bytes, but got {})",
7178 Self::ENCODED_LEN,
7179 __tmp.remaining(),
7180 )
7181 }
7182 __tmp.put_u32_le(self.time_boot_ms);
7183 __tmp.put_f32_le(self.roll);
7184 __tmp.put_f32_le(self.pitch);
7185 __tmp.put_f32_le(self.yaw);
7186 __tmp.put_f32_le(self.rollspeed);
7187 __tmp.put_f32_le(self.pitchspeed);
7188 __tmp.put_f32_le(self.yawspeed);
7189 if matches!(version, MavlinkVersion::V2) {
7190 let len = __tmp.len();
7191 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7192 } else {
7193 __tmp.len()
7194 }
7195 }
7196}
7197#[doc = "The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0)."]
7198#[doc = ""]
7199#[doc = "ID: 31"]
7200#[derive(Debug, Clone, PartialEq)]
7201#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7202#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7203#[cfg_attr(feature = "ts", derive(TS))]
7204#[cfg_attr(feature = "ts", ts(export))]
7205pub struct ATTITUDE_QUATERNION_DATA {
7206 #[doc = "Timestamp (time since system boot)."]
7207 pub time_boot_ms: u32,
7208 #[doc = "Quaternion component 1, w (1 in null-rotation)"]
7209 pub q1: f32,
7210 #[doc = "Quaternion component 2, x (0 in null-rotation)"]
7211 pub q2: f32,
7212 #[doc = "Quaternion component 3, y (0 in null-rotation)"]
7213 pub q3: f32,
7214 #[doc = "Quaternion component 4, z (0 in null-rotation)"]
7215 pub q4: f32,
7216 #[doc = "Roll angular speed"]
7217 pub rollspeed: f32,
7218 #[doc = "Pitch angular speed"]
7219 pub pitchspeed: f32,
7220 #[doc = "Yaw angular speed"]
7221 pub yawspeed: f32,
7222 #[doc = "Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode."]
7223 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7224 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7225 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
7226 pub repr_offset_q: [f32; 4],
7227}
7228impl ATTITUDE_QUATERNION_DATA {
7229 pub const ENCODED_LEN: usize = 48usize;
7230 pub const DEFAULT: Self = Self {
7231 time_boot_ms: 0_u32,
7232 q1: 0.0_f32,
7233 q2: 0.0_f32,
7234 q3: 0.0_f32,
7235 q4: 0.0_f32,
7236 rollspeed: 0.0_f32,
7237 pitchspeed: 0.0_f32,
7238 yawspeed: 0.0_f32,
7239 repr_offset_q: [0.0_f32; 4usize],
7240 };
7241 #[cfg(feature = "arbitrary")]
7242 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7243 use arbitrary::{Arbitrary, Unstructured};
7244 let mut buf = [0u8; 1024];
7245 rng.fill_bytes(&mut buf);
7246 let mut unstructured = Unstructured::new(&buf);
7247 Self::arbitrary(&mut unstructured).unwrap_or_default()
7248 }
7249}
7250impl Default for ATTITUDE_QUATERNION_DATA {
7251 fn default() -> Self {
7252 Self::DEFAULT.clone()
7253 }
7254}
7255impl MessageData for ATTITUDE_QUATERNION_DATA {
7256 type Message = MavMessage;
7257 const ID: u32 = 31u32;
7258 const NAME: &'static str = "ATTITUDE_QUATERNION";
7259 const EXTRA_CRC: u8 = 246u8;
7260 const ENCODED_LEN: usize = 48usize;
7261 fn deser(
7262 _version: MavlinkVersion,
7263 __input: &[u8],
7264 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7265 let avail_len = __input.len();
7266 let mut payload_buf = [0; Self::ENCODED_LEN];
7267 let mut buf = if avail_len < Self::ENCODED_LEN {
7268 payload_buf[0..avail_len].copy_from_slice(__input);
7269 Bytes::new(&payload_buf)
7270 } else {
7271 Bytes::new(__input)
7272 };
7273 let mut __struct = Self::default();
7274 __struct.time_boot_ms = buf.get_u32_le()?;
7275 __struct.q1 = buf.get_f32_le()?;
7276 __struct.q2 = buf.get_f32_le()?;
7277 __struct.q3 = buf.get_f32_le()?;
7278 __struct.q4 = buf.get_f32_le()?;
7279 __struct.rollspeed = buf.get_f32_le()?;
7280 __struct.pitchspeed = buf.get_f32_le()?;
7281 __struct.yawspeed = buf.get_f32_le()?;
7282 for v in &mut __struct.repr_offset_q {
7283 let val = buf.get_f32_le()?;
7284 *v = val;
7285 }
7286 Ok(__struct)
7287 }
7288 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7289 let mut __tmp = BytesMut::new(bytes);
7290 #[allow(clippy::absurd_extreme_comparisons)]
7291 #[allow(unused_comparisons)]
7292 if __tmp.remaining() < Self::ENCODED_LEN {
7293 panic!(
7294 "buffer is too small (need {} bytes, but got {})",
7295 Self::ENCODED_LEN,
7296 __tmp.remaining(),
7297 )
7298 }
7299 __tmp.put_u32_le(self.time_boot_ms);
7300 __tmp.put_f32_le(self.q1);
7301 __tmp.put_f32_le(self.q2);
7302 __tmp.put_f32_le(self.q3);
7303 __tmp.put_f32_le(self.q4);
7304 __tmp.put_f32_le(self.rollspeed);
7305 __tmp.put_f32_le(self.pitchspeed);
7306 __tmp.put_f32_le(self.yawspeed);
7307 if matches!(version, MavlinkVersion::V2) {
7308 for val in &self.repr_offset_q {
7309 __tmp.put_f32_le(*val);
7310 }
7311 let len = __tmp.len();
7312 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7313 } else {
7314 __tmp.len()
7315 }
7316 }
7317}
7318#[doc = "The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0)."]
7319#[doc = ""]
7320#[doc = "ID: 61"]
7321#[derive(Debug, Clone, PartialEq)]
7322#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7323#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7324#[cfg_attr(feature = "ts", derive(TS))]
7325#[cfg_attr(feature = "ts", ts(export))]
7326pub struct ATTITUDE_QUATERNION_COV_DATA {
7327 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
7328 pub time_usec: u64,
7329 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)"]
7330 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7331 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
7332 pub q: [f32; 4],
7333 #[doc = "Roll angular speed"]
7334 pub rollspeed: f32,
7335 #[doc = "Pitch angular speed"]
7336 pub pitchspeed: f32,
7337 #[doc = "Yaw angular speed"]
7338 pub yawspeed: f32,
7339 #[doc = "Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array."]
7340 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7341 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
7342 pub covariance: [f32; 9],
7343}
7344impl ATTITUDE_QUATERNION_COV_DATA {
7345 pub const ENCODED_LEN: usize = 72usize;
7346 pub const DEFAULT: Self = Self {
7347 time_usec: 0_u64,
7348 q: [0.0_f32; 4usize],
7349 rollspeed: 0.0_f32,
7350 pitchspeed: 0.0_f32,
7351 yawspeed: 0.0_f32,
7352 covariance: [0.0_f32; 9usize],
7353 };
7354 #[cfg(feature = "arbitrary")]
7355 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7356 use arbitrary::{Arbitrary, Unstructured};
7357 let mut buf = [0u8; 1024];
7358 rng.fill_bytes(&mut buf);
7359 let mut unstructured = Unstructured::new(&buf);
7360 Self::arbitrary(&mut unstructured).unwrap_or_default()
7361 }
7362}
7363impl Default for ATTITUDE_QUATERNION_COV_DATA {
7364 fn default() -> Self {
7365 Self::DEFAULT.clone()
7366 }
7367}
7368impl MessageData for ATTITUDE_QUATERNION_COV_DATA {
7369 type Message = MavMessage;
7370 const ID: u32 = 61u32;
7371 const NAME: &'static str = "ATTITUDE_QUATERNION_COV";
7372 const EXTRA_CRC: u8 = 167u8;
7373 const ENCODED_LEN: usize = 72usize;
7374 fn deser(
7375 _version: MavlinkVersion,
7376 __input: &[u8],
7377 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7378 let avail_len = __input.len();
7379 let mut payload_buf = [0; Self::ENCODED_LEN];
7380 let mut buf = if avail_len < Self::ENCODED_LEN {
7381 payload_buf[0..avail_len].copy_from_slice(__input);
7382 Bytes::new(&payload_buf)
7383 } else {
7384 Bytes::new(__input)
7385 };
7386 let mut __struct = Self::default();
7387 __struct.time_usec = buf.get_u64_le()?;
7388 for v in &mut __struct.q {
7389 let val = buf.get_f32_le()?;
7390 *v = val;
7391 }
7392 __struct.rollspeed = buf.get_f32_le()?;
7393 __struct.pitchspeed = buf.get_f32_le()?;
7394 __struct.yawspeed = buf.get_f32_le()?;
7395 for v in &mut __struct.covariance {
7396 let val = buf.get_f32_le()?;
7397 *v = val;
7398 }
7399 Ok(__struct)
7400 }
7401 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7402 let mut __tmp = BytesMut::new(bytes);
7403 #[allow(clippy::absurd_extreme_comparisons)]
7404 #[allow(unused_comparisons)]
7405 if __tmp.remaining() < Self::ENCODED_LEN {
7406 panic!(
7407 "buffer is too small (need {} bytes, but got {})",
7408 Self::ENCODED_LEN,
7409 __tmp.remaining(),
7410 )
7411 }
7412 __tmp.put_u64_le(self.time_usec);
7413 for val in &self.q {
7414 __tmp.put_f32_le(*val);
7415 }
7416 __tmp.put_f32_le(self.rollspeed);
7417 __tmp.put_f32_le(self.pitchspeed);
7418 __tmp.put_f32_le(self.yawspeed);
7419 for val in &self.covariance {
7420 __tmp.put_f32_le(*val);
7421 }
7422 if matches!(version, MavlinkVersion::V2) {
7423 let len = __tmp.len();
7424 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7425 } else {
7426 __tmp.len()
7427 }
7428 }
7429}
7430#[doc = "Reports the current commanded attitude of the vehicle as specified by the autopilot. This should match the commands sent in a SET_ATTITUDE_TARGET message if the vehicle is being controlled this way."]
7431#[doc = ""]
7432#[doc = "ID: 83"]
7433#[derive(Debug, Clone, PartialEq)]
7434#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7435#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7436#[cfg_attr(feature = "ts", derive(TS))]
7437#[cfg_attr(feature = "ts", ts(export))]
7438pub struct ATTITUDE_TARGET_DATA {
7439 #[doc = "Timestamp (time since system boot)."]
7440 pub time_boot_ms: u32,
7441 #[doc = "Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
7442 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7443 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
7444 pub q: [f32; 4],
7445 #[doc = "Body roll rate"]
7446 pub body_roll_rate: f32,
7447 #[doc = "Body pitch rate"]
7448 pub body_pitch_rate: f32,
7449 #[doc = "Body yaw rate"]
7450 pub body_yaw_rate: f32,
7451 #[doc = "Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)"]
7452 pub thrust: f32,
7453 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
7454 pub type_mask: AttitudeTargetTypemask,
7455}
7456impl ATTITUDE_TARGET_DATA {
7457 pub const ENCODED_LEN: usize = 37usize;
7458 pub const DEFAULT: Self = Self {
7459 time_boot_ms: 0_u32,
7460 q: [0.0_f32; 4usize],
7461 body_roll_rate: 0.0_f32,
7462 body_pitch_rate: 0.0_f32,
7463 body_yaw_rate: 0.0_f32,
7464 thrust: 0.0_f32,
7465 type_mask: AttitudeTargetTypemask::DEFAULT,
7466 };
7467 #[cfg(feature = "arbitrary")]
7468 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7469 use arbitrary::{Arbitrary, Unstructured};
7470 let mut buf = [0u8; 1024];
7471 rng.fill_bytes(&mut buf);
7472 let mut unstructured = Unstructured::new(&buf);
7473 Self::arbitrary(&mut unstructured).unwrap_or_default()
7474 }
7475}
7476impl Default for ATTITUDE_TARGET_DATA {
7477 fn default() -> Self {
7478 Self::DEFAULT.clone()
7479 }
7480}
7481impl MessageData for ATTITUDE_TARGET_DATA {
7482 type Message = MavMessage;
7483 const ID: u32 = 83u32;
7484 const NAME: &'static str = "ATTITUDE_TARGET";
7485 const EXTRA_CRC: u8 = 22u8;
7486 const ENCODED_LEN: usize = 37usize;
7487 fn deser(
7488 _version: MavlinkVersion,
7489 __input: &[u8],
7490 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7491 let avail_len = __input.len();
7492 let mut payload_buf = [0; Self::ENCODED_LEN];
7493 let mut buf = if avail_len < Self::ENCODED_LEN {
7494 payload_buf[0..avail_len].copy_from_slice(__input);
7495 Bytes::new(&payload_buf)
7496 } else {
7497 Bytes::new(__input)
7498 };
7499 let mut __struct = Self::default();
7500 __struct.time_boot_ms = buf.get_u32_le()?;
7501 for v in &mut __struct.q {
7502 let val = buf.get_f32_le()?;
7503 *v = val;
7504 }
7505 __struct.body_roll_rate = buf.get_f32_le()?;
7506 __struct.body_pitch_rate = buf.get_f32_le()?;
7507 __struct.body_yaw_rate = buf.get_f32_le()?;
7508 __struct.thrust = buf.get_f32_le()?;
7509 let tmp = buf.get_u8()?;
7510 __struct.type_mask =
7511 AttitudeTargetTypemask::from_bits(tmp as <AttitudeTargetTypemask as Flags>::Bits)
7512 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
7513 flag_type: "AttitudeTargetTypemask",
7514 value: tmp as u64,
7515 })?;
7516 Ok(__struct)
7517 }
7518 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7519 let mut __tmp = BytesMut::new(bytes);
7520 #[allow(clippy::absurd_extreme_comparisons)]
7521 #[allow(unused_comparisons)]
7522 if __tmp.remaining() < Self::ENCODED_LEN {
7523 panic!(
7524 "buffer is too small (need {} bytes, but got {})",
7525 Self::ENCODED_LEN,
7526 __tmp.remaining(),
7527 )
7528 }
7529 __tmp.put_u32_le(self.time_boot_ms);
7530 for val in &self.q {
7531 __tmp.put_f32_le(*val);
7532 }
7533 __tmp.put_f32_le(self.body_roll_rate);
7534 __tmp.put_f32_le(self.body_pitch_rate);
7535 __tmp.put_f32_le(self.body_yaw_rate);
7536 __tmp.put_f32_le(self.thrust);
7537 __tmp.put_u8(self.type_mask.bits() as u8);
7538 if matches!(version, MavlinkVersion::V2) {
7539 let len = __tmp.len();
7540 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7541 } else {
7542 __tmp.len()
7543 }
7544 }
7545}
7546#[doc = "Motion capture attitude and position."]
7547#[doc = ""]
7548#[doc = "ID: 138"]
7549#[derive(Debug, Clone, PartialEq)]
7550#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7551#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7552#[cfg_attr(feature = "ts", derive(TS))]
7553#[cfg_attr(feature = "ts", ts(export))]
7554pub struct ATT_POS_MOCAP_DATA {
7555 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
7556 pub time_usec: u64,
7557 #[doc = "Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
7558 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7559 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
7560 pub q: [f32; 4],
7561 #[doc = "X position (NED)"]
7562 pub x: f32,
7563 #[doc = "Y position (NED)"]
7564 pub y: f32,
7565 #[doc = "Z position (NED)"]
7566 pub z: f32,
7567 #[doc = "Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
7568 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7569 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7570 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
7571 pub covariance: [f32; 21],
7572}
7573impl ATT_POS_MOCAP_DATA {
7574 pub const ENCODED_LEN: usize = 120usize;
7575 pub const DEFAULT: Self = Self {
7576 time_usec: 0_u64,
7577 q: [0.0_f32; 4usize],
7578 x: 0.0_f32,
7579 y: 0.0_f32,
7580 z: 0.0_f32,
7581 covariance: [0.0_f32; 21usize],
7582 };
7583 #[cfg(feature = "arbitrary")]
7584 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7585 use arbitrary::{Arbitrary, Unstructured};
7586 let mut buf = [0u8; 1024];
7587 rng.fill_bytes(&mut buf);
7588 let mut unstructured = Unstructured::new(&buf);
7589 Self::arbitrary(&mut unstructured).unwrap_or_default()
7590 }
7591}
7592impl Default for ATT_POS_MOCAP_DATA {
7593 fn default() -> Self {
7594 Self::DEFAULT.clone()
7595 }
7596}
7597impl MessageData for ATT_POS_MOCAP_DATA {
7598 type Message = MavMessage;
7599 const ID: u32 = 138u32;
7600 const NAME: &'static str = "ATT_POS_MOCAP";
7601 const EXTRA_CRC: u8 = 109u8;
7602 const ENCODED_LEN: usize = 120usize;
7603 fn deser(
7604 _version: MavlinkVersion,
7605 __input: &[u8],
7606 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7607 let avail_len = __input.len();
7608 let mut payload_buf = [0; Self::ENCODED_LEN];
7609 let mut buf = if avail_len < Self::ENCODED_LEN {
7610 payload_buf[0..avail_len].copy_from_slice(__input);
7611 Bytes::new(&payload_buf)
7612 } else {
7613 Bytes::new(__input)
7614 };
7615 let mut __struct = Self::default();
7616 __struct.time_usec = buf.get_u64_le()?;
7617 for v in &mut __struct.q {
7618 let val = buf.get_f32_le()?;
7619 *v = val;
7620 }
7621 __struct.x = buf.get_f32_le()?;
7622 __struct.y = buf.get_f32_le()?;
7623 __struct.z = buf.get_f32_le()?;
7624 for v in &mut __struct.covariance {
7625 let val = buf.get_f32_le()?;
7626 *v = val;
7627 }
7628 Ok(__struct)
7629 }
7630 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7631 let mut __tmp = BytesMut::new(bytes);
7632 #[allow(clippy::absurd_extreme_comparisons)]
7633 #[allow(unused_comparisons)]
7634 if __tmp.remaining() < Self::ENCODED_LEN {
7635 panic!(
7636 "buffer is too small (need {} bytes, but got {})",
7637 Self::ENCODED_LEN,
7638 __tmp.remaining(),
7639 )
7640 }
7641 __tmp.put_u64_le(self.time_usec);
7642 for val in &self.q {
7643 __tmp.put_f32_le(*val);
7644 }
7645 __tmp.put_f32_le(self.x);
7646 __tmp.put_f32_le(self.y);
7647 __tmp.put_f32_le(self.z);
7648 if matches!(version, MavlinkVersion::V2) {
7649 for val in &self.covariance {
7650 __tmp.put_f32_le(*val);
7651 }
7652 let len = __tmp.len();
7653 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7654 } else {
7655 __tmp.len()
7656 }
7657 }
7658}
7659#[doc = "Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety."]
7660#[doc = ""]
7661#[doc = "ID: 7"]
7662#[derive(Debug, Clone, PartialEq)]
7663#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7664#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7665#[cfg_attr(feature = "ts", derive(TS))]
7666#[cfg_attr(feature = "ts", ts(export))]
7667pub struct AUTH_KEY_DATA {
7668 #[doc = "key"]
7669 #[cfg_attr(feature = "ts", ts(type = "string"))]
7670 pub key: CharArray<32>,
7671}
7672impl AUTH_KEY_DATA {
7673 pub const ENCODED_LEN: usize = 32usize;
7674 pub const DEFAULT: Self = Self {
7675 key: CharArray::new([0_u8; 32usize]),
7676 };
7677 #[cfg(feature = "arbitrary")]
7678 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7679 use arbitrary::{Arbitrary, Unstructured};
7680 let mut buf = [0u8; 1024];
7681 rng.fill_bytes(&mut buf);
7682 let mut unstructured = Unstructured::new(&buf);
7683 Self::arbitrary(&mut unstructured).unwrap_or_default()
7684 }
7685}
7686impl Default for AUTH_KEY_DATA {
7687 fn default() -> Self {
7688 Self::DEFAULT.clone()
7689 }
7690}
7691impl MessageData for AUTH_KEY_DATA {
7692 type Message = MavMessage;
7693 const ID: u32 = 7u32;
7694 const NAME: &'static str = "AUTH_KEY";
7695 const EXTRA_CRC: u8 = 119u8;
7696 const ENCODED_LEN: usize = 32usize;
7697 fn deser(
7698 _version: MavlinkVersion,
7699 __input: &[u8],
7700 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7701 let avail_len = __input.len();
7702 let mut payload_buf = [0; Self::ENCODED_LEN];
7703 let mut buf = if avail_len < Self::ENCODED_LEN {
7704 payload_buf[0..avail_len].copy_from_slice(__input);
7705 Bytes::new(&payload_buf)
7706 } else {
7707 Bytes::new(__input)
7708 };
7709 let mut __struct = Self::default();
7710 let mut tmp = [0_u8; 32usize];
7711 for v in &mut tmp {
7712 *v = buf.get_u8()?;
7713 }
7714 __struct.key = CharArray::new(tmp);
7715 Ok(__struct)
7716 }
7717 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7718 let mut __tmp = BytesMut::new(bytes);
7719 #[allow(clippy::absurd_extreme_comparisons)]
7720 #[allow(unused_comparisons)]
7721 if __tmp.remaining() < Self::ENCODED_LEN {
7722 panic!(
7723 "buffer is too small (need {} bytes, but got {})",
7724 Self::ENCODED_LEN,
7725 __tmp.remaining(),
7726 )
7727 }
7728 for val in &self.key {
7729 __tmp.put_u8(*val);
7730 }
7731 if matches!(version, MavlinkVersion::V2) {
7732 let len = __tmp.len();
7733 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7734 } else {
7735 __tmp.len()
7736 }
7737 }
7738}
7739#[doc = "Low level message containing autopilot state relevant for a gimbal device. This message is to be sent from the autopilot to the gimbal device component. The data of this message are for the gimbal device's estimator corrections, in particular horizon compensation, as well as indicates autopilot control intentions, e.g. feed forward angular control in the z-axis."]
7740#[doc = ""]
7741#[doc = "ID: 286"]
7742#[derive(Debug, Clone, PartialEq)]
7743#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7744#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7745#[cfg_attr(feature = "ts", derive(TS))]
7746#[cfg_attr(feature = "ts", ts(export))]
7747pub struct AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA {
7748 #[doc = "Timestamp (time since system boot)."]
7749 pub time_boot_us: u64,
7750 #[doc = "Quaternion components of autopilot attitude: w, x, y, z (1 0 0 0 is the null-rotation, Hamilton convention)."]
7751 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7752 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
7753 pub q: [f32; 4],
7754 #[doc = "Estimated delay of the attitude data. 0 if unknown."]
7755 pub q_estimated_delay_us: u32,
7756 #[doc = "X Speed in NED (North, East, Down). NAN if unknown."]
7757 pub vx: f32,
7758 #[doc = "Y Speed in NED (North, East, Down). NAN if unknown."]
7759 pub vy: f32,
7760 #[doc = "Z Speed in NED (North, East, Down). NAN if unknown."]
7761 pub vz: f32,
7762 #[doc = "Estimated delay of the speed data. 0 if unknown."]
7763 pub v_estimated_delay_us: u32,
7764 #[doc = "Feed forward Z component of angular velocity (positive: yawing to the right). NaN to be ignored. This is to indicate if the autopilot is actively yawing."]
7765 pub feed_forward_angular_velocity_z: f32,
7766 #[doc = "Bitmap indicating which estimator outputs are valid."]
7767 pub estimator_status: EstimatorStatusFlags,
7768 #[doc = "System ID"]
7769 pub target_system: u8,
7770 #[doc = "Component ID"]
7771 pub target_component: u8,
7772 #[doc = "The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown."]
7773 pub landed_state: MavLandedState,
7774 #[doc = "Z component of angular velocity in NED (North, East, Down). NaN if unknown."]
7775 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7776 pub angular_velocity_z: f32,
7777}
7778impl AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA {
7779 pub const ENCODED_LEN: usize = 57usize;
7780 pub const DEFAULT: Self = Self {
7781 time_boot_us: 0_u64,
7782 q: [0.0_f32; 4usize],
7783 q_estimated_delay_us: 0_u32,
7784 vx: 0.0_f32,
7785 vy: 0.0_f32,
7786 vz: 0.0_f32,
7787 v_estimated_delay_us: 0_u32,
7788 feed_forward_angular_velocity_z: 0.0_f32,
7789 estimator_status: EstimatorStatusFlags::DEFAULT,
7790 target_system: 0_u8,
7791 target_component: 0_u8,
7792 landed_state: MavLandedState::DEFAULT,
7793 angular_velocity_z: 0.0_f32,
7794 };
7795 #[cfg(feature = "arbitrary")]
7796 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7797 use arbitrary::{Arbitrary, Unstructured};
7798 let mut buf = [0u8; 1024];
7799 rng.fill_bytes(&mut buf);
7800 let mut unstructured = Unstructured::new(&buf);
7801 Self::arbitrary(&mut unstructured).unwrap_or_default()
7802 }
7803}
7804impl Default for AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA {
7805 fn default() -> Self {
7806 Self::DEFAULT.clone()
7807 }
7808}
7809impl MessageData for AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA {
7810 type Message = MavMessage;
7811 const ID: u32 = 286u32;
7812 const NAME: &'static str = "AUTOPILOT_STATE_FOR_GIMBAL_DEVICE";
7813 const EXTRA_CRC: u8 = 210u8;
7814 const ENCODED_LEN: usize = 57usize;
7815 fn deser(
7816 _version: MavlinkVersion,
7817 __input: &[u8],
7818 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7819 let avail_len = __input.len();
7820 let mut payload_buf = [0; Self::ENCODED_LEN];
7821 let mut buf = if avail_len < Self::ENCODED_LEN {
7822 payload_buf[0..avail_len].copy_from_slice(__input);
7823 Bytes::new(&payload_buf)
7824 } else {
7825 Bytes::new(__input)
7826 };
7827 let mut __struct = Self::default();
7828 __struct.time_boot_us = buf.get_u64_le()?;
7829 for v in &mut __struct.q {
7830 let val = buf.get_f32_le()?;
7831 *v = val;
7832 }
7833 __struct.q_estimated_delay_us = buf.get_u32_le()?;
7834 __struct.vx = buf.get_f32_le()?;
7835 __struct.vy = buf.get_f32_le()?;
7836 __struct.vz = buf.get_f32_le()?;
7837 __struct.v_estimated_delay_us = buf.get_u32_le()?;
7838 __struct.feed_forward_angular_velocity_z = buf.get_f32_le()?;
7839 let tmp = buf.get_u16_le()?;
7840 __struct.estimator_status = EstimatorStatusFlags::from_bits(
7841 tmp as <EstimatorStatusFlags as Flags>::Bits,
7842 )
7843 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
7844 flag_type: "EstimatorStatusFlags",
7845 value: tmp as u64,
7846 })?;
7847 __struct.target_system = buf.get_u8()?;
7848 __struct.target_component = buf.get_u8()?;
7849 let tmp = buf.get_u8()?;
7850 __struct.landed_state =
7851 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
7852 enum_type: "MavLandedState",
7853 value: tmp as u64,
7854 })?;
7855 __struct.angular_velocity_z = buf.get_f32_le()?;
7856 Ok(__struct)
7857 }
7858 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7859 let mut __tmp = BytesMut::new(bytes);
7860 #[allow(clippy::absurd_extreme_comparisons)]
7861 #[allow(unused_comparisons)]
7862 if __tmp.remaining() < Self::ENCODED_LEN {
7863 panic!(
7864 "buffer is too small (need {} bytes, but got {})",
7865 Self::ENCODED_LEN,
7866 __tmp.remaining(),
7867 )
7868 }
7869 __tmp.put_u64_le(self.time_boot_us);
7870 for val in &self.q {
7871 __tmp.put_f32_le(*val);
7872 }
7873 __tmp.put_u32_le(self.q_estimated_delay_us);
7874 __tmp.put_f32_le(self.vx);
7875 __tmp.put_f32_le(self.vy);
7876 __tmp.put_f32_le(self.vz);
7877 __tmp.put_u32_le(self.v_estimated_delay_us);
7878 __tmp.put_f32_le(self.feed_forward_angular_velocity_z);
7879 __tmp.put_u16_le(self.estimator_status.bits() as u16);
7880 __tmp.put_u8(self.target_system);
7881 __tmp.put_u8(self.target_component);
7882 __tmp.put_u8(self.landed_state as u8);
7883 if matches!(version, MavlinkVersion::V2) {
7884 __tmp.put_f32_le(self.angular_velocity_z);
7885 let len = __tmp.len();
7886 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7887 } else {
7888 __tmp.len()
7889 }
7890 }
7891}
7892#[doc = "Version and capability of autopilot software. This should be emitted in response to a request with MAV_CMD_REQUEST_MESSAGE."]
7893#[doc = ""]
7894#[doc = "ID: 148"]
7895#[derive(Debug, Clone, PartialEq)]
7896#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7897#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7898#[cfg_attr(feature = "ts", derive(TS))]
7899#[cfg_attr(feature = "ts", ts(export))]
7900pub struct AUTOPILOT_VERSION_DATA {
7901 #[doc = "Bitmap of capabilities"]
7902 pub capabilities: MavProtocolCapability,
7903 #[doc = "UID if provided by hardware (see uid2)"]
7904 pub uid: u64,
7905 #[doc = "Firmware version number. The field must be encoded as 4 bytes, where each byte (shown from MSB to LSB) is part of a semantic version: (major) (minor) (patch) (FIRMWARE_VERSION_TYPE)."]
7906 pub flight_sw_version: u32,
7907 #[doc = "Middleware version number"]
7908 pub middleware_sw_version: u32,
7909 #[doc = "Operating system version number"]
7910 pub os_sw_version: u32,
7911 #[doc = "HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify <https://github.com/PX4/PX4-Bootloader/blob/master/board_types.txt>"]
7912 pub board_version: u32,
7913 #[doc = "ID of the board vendor"]
7914 pub vendor_id: u16,
7915 #[doc = "ID of the product"]
7916 pub product_id: u16,
7917 #[doc = "Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases."]
7918 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7919 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
7920 pub flight_custom_version: [u8; 8],
7921 #[doc = "Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases."]
7922 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7923 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
7924 pub middleware_custom_version: [u8; 8],
7925 #[doc = "Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases."]
7926 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7927 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
7928 pub os_custom_version: [u8; 8],
7929 #[doc = "UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid)"]
7930 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7931 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7932 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
7933 pub uid2: [u8; 18],
7934}
7935impl AUTOPILOT_VERSION_DATA {
7936 pub const ENCODED_LEN: usize = 78usize;
7937 pub const DEFAULT: Self = Self {
7938 capabilities: MavProtocolCapability::DEFAULT,
7939 uid: 0_u64,
7940 flight_sw_version: 0_u32,
7941 middleware_sw_version: 0_u32,
7942 os_sw_version: 0_u32,
7943 board_version: 0_u32,
7944 vendor_id: 0_u16,
7945 product_id: 0_u16,
7946 flight_custom_version: [0_u8; 8usize],
7947 middleware_custom_version: [0_u8; 8usize],
7948 os_custom_version: [0_u8; 8usize],
7949 uid2: [0_u8; 18usize],
7950 };
7951 #[cfg(feature = "arbitrary")]
7952 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7953 use arbitrary::{Arbitrary, Unstructured};
7954 let mut buf = [0u8; 1024];
7955 rng.fill_bytes(&mut buf);
7956 let mut unstructured = Unstructured::new(&buf);
7957 Self::arbitrary(&mut unstructured).unwrap_or_default()
7958 }
7959}
7960impl Default for AUTOPILOT_VERSION_DATA {
7961 fn default() -> Self {
7962 Self::DEFAULT.clone()
7963 }
7964}
7965impl MessageData for AUTOPILOT_VERSION_DATA {
7966 type Message = MavMessage;
7967 const ID: u32 = 148u32;
7968 const NAME: &'static str = "AUTOPILOT_VERSION";
7969 const EXTRA_CRC: u8 = 178u8;
7970 const ENCODED_LEN: usize = 78usize;
7971 fn deser(
7972 _version: MavlinkVersion,
7973 __input: &[u8],
7974 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7975 let avail_len = __input.len();
7976 let mut payload_buf = [0; Self::ENCODED_LEN];
7977 let mut buf = if avail_len < Self::ENCODED_LEN {
7978 payload_buf[0..avail_len].copy_from_slice(__input);
7979 Bytes::new(&payload_buf)
7980 } else {
7981 Bytes::new(__input)
7982 };
7983 let mut __struct = Self::default();
7984 let tmp = buf.get_u64_le()?;
7985 __struct.capabilities = MavProtocolCapability::from_bits(
7986 tmp as <MavProtocolCapability as Flags>::Bits,
7987 )
7988 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
7989 flag_type: "MavProtocolCapability",
7990 value: tmp as u64,
7991 })?;
7992 __struct.uid = buf.get_u64_le()?;
7993 __struct.flight_sw_version = buf.get_u32_le()?;
7994 __struct.middleware_sw_version = buf.get_u32_le()?;
7995 __struct.os_sw_version = buf.get_u32_le()?;
7996 __struct.board_version = buf.get_u32_le()?;
7997 __struct.vendor_id = buf.get_u16_le()?;
7998 __struct.product_id = buf.get_u16_le()?;
7999 for v in &mut __struct.flight_custom_version {
8000 let val = buf.get_u8()?;
8001 *v = val;
8002 }
8003 for v in &mut __struct.middleware_custom_version {
8004 let val = buf.get_u8()?;
8005 *v = val;
8006 }
8007 for v in &mut __struct.os_custom_version {
8008 let val = buf.get_u8()?;
8009 *v = val;
8010 }
8011 for v in &mut __struct.uid2 {
8012 let val = buf.get_u8()?;
8013 *v = val;
8014 }
8015 Ok(__struct)
8016 }
8017 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8018 let mut __tmp = BytesMut::new(bytes);
8019 #[allow(clippy::absurd_extreme_comparisons)]
8020 #[allow(unused_comparisons)]
8021 if __tmp.remaining() < Self::ENCODED_LEN {
8022 panic!(
8023 "buffer is too small (need {} bytes, but got {})",
8024 Self::ENCODED_LEN,
8025 __tmp.remaining(),
8026 )
8027 }
8028 __tmp.put_u64_le(self.capabilities.bits() as u64);
8029 __tmp.put_u64_le(self.uid);
8030 __tmp.put_u32_le(self.flight_sw_version);
8031 __tmp.put_u32_le(self.middleware_sw_version);
8032 __tmp.put_u32_le(self.os_sw_version);
8033 __tmp.put_u32_le(self.board_version);
8034 __tmp.put_u16_le(self.vendor_id);
8035 __tmp.put_u16_le(self.product_id);
8036 for val in &self.flight_custom_version {
8037 __tmp.put_u8(*val);
8038 }
8039 for val in &self.middleware_custom_version {
8040 __tmp.put_u8(*val);
8041 }
8042 for val in &self.os_custom_version {
8043 __tmp.put_u8(*val);
8044 }
8045 if matches!(version, MavlinkVersion::V2) {
8046 for val in &self.uid2 {
8047 __tmp.put_u8(*val);
8048 }
8049 let len = __tmp.len();
8050 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8051 } else {
8052 __tmp.len()
8053 }
8054 }
8055}
8056#[doc = "Information about a flight mode. The message can be enumerated to get information for all modes, or requested for a particular mode, using MAV_CMD_REQUEST_MESSAGE. Specify 0 in param2 to request that the message is emitted for all available modes or the specific index for just one mode. The modes must be available/settable for the current vehicle/frame type. Each mode should only be emitted once (even if it is both standard and custom). Note that the current mode should be emitted in CURRENT_MODE, and that if the mode list can change then AVAILABLE_MODES_MONITOR must be emitted on first change and subsequently streamed. See <https://mavlink.io/en/services/standard_modes.html>."]
8057#[doc = ""]
8058#[doc = "ID: 435"]
8059#[derive(Debug, Clone, PartialEq)]
8060#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8061#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8062#[cfg_attr(feature = "ts", derive(TS))]
8063#[cfg_attr(feature = "ts", ts(export))]
8064pub struct AVAILABLE_MODES_DATA {
8065 #[doc = "A bitfield for use for autopilot-specific flags"]
8066 pub custom_mode: u32,
8067 #[doc = "Mode properties."]
8068 pub properties: MavModeProperty,
8069 #[doc = "The total number of available modes for the current vehicle type."]
8070 pub number_modes: u8,
8071 #[doc = "The current mode index within number_modes, indexed from 1. The index is not guaranteed to be persistent, and may change between reboots or if the set of modes change."]
8072 pub mode_index: u8,
8073 #[doc = "Standard mode."]
8074 pub standard_mode: MavStandardMode,
8075 #[doc = "Name of custom mode, with null termination character. Should be omitted for standard modes."]
8076 #[cfg_attr(feature = "ts", ts(type = "string"))]
8077 pub mode_name: CharArray<35>,
8078}
8079impl AVAILABLE_MODES_DATA {
8080 pub const ENCODED_LEN: usize = 46usize;
8081 pub const DEFAULT: Self = Self {
8082 custom_mode: 0_u32,
8083 properties: MavModeProperty::DEFAULT,
8084 number_modes: 0_u8,
8085 mode_index: 0_u8,
8086 standard_mode: MavStandardMode::DEFAULT,
8087 mode_name: CharArray::new([0_u8; 35usize]),
8088 };
8089 #[cfg(feature = "arbitrary")]
8090 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8091 use arbitrary::{Arbitrary, Unstructured};
8092 let mut buf = [0u8; 1024];
8093 rng.fill_bytes(&mut buf);
8094 let mut unstructured = Unstructured::new(&buf);
8095 Self::arbitrary(&mut unstructured).unwrap_or_default()
8096 }
8097}
8098impl Default for AVAILABLE_MODES_DATA {
8099 fn default() -> Self {
8100 Self::DEFAULT.clone()
8101 }
8102}
8103impl MessageData for AVAILABLE_MODES_DATA {
8104 type Message = MavMessage;
8105 const ID: u32 = 435u32;
8106 const NAME: &'static str = "AVAILABLE_MODES";
8107 const EXTRA_CRC: u8 = 134u8;
8108 const ENCODED_LEN: usize = 46usize;
8109 fn deser(
8110 _version: MavlinkVersion,
8111 __input: &[u8],
8112 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8113 let avail_len = __input.len();
8114 let mut payload_buf = [0; Self::ENCODED_LEN];
8115 let mut buf = if avail_len < Self::ENCODED_LEN {
8116 payload_buf[0..avail_len].copy_from_slice(__input);
8117 Bytes::new(&payload_buf)
8118 } else {
8119 Bytes::new(__input)
8120 };
8121 let mut __struct = Self::default();
8122 __struct.custom_mode = buf.get_u32_le()?;
8123 let tmp = buf.get_u32_le()?;
8124 __struct.properties = MavModeProperty::from_bits(tmp as <MavModeProperty as Flags>::Bits)
8125 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
8126 flag_type: "MavModeProperty",
8127 value: tmp as u64,
8128 })?;
8129 __struct.number_modes = buf.get_u8()?;
8130 __struct.mode_index = buf.get_u8()?;
8131 let tmp = buf.get_u8()?;
8132 __struct.standard_mode =
8133 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8134 enum_type: "MavStandardMode",
8135 value: tmp as u64,
8136 })?;
8137 let mut tmp = [0_u8; 35usize];
8138 for v in &mut tmp {
8139 *v = buf.get_u8()?;
8140 }
8141 __struct.mode_name = CharArray::new(tmp);
8142 Ok(__struct)
8143 }
8144 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8145 let mut __tmp = BytesMut::new(bytes);
8146 #[allow(clippy::absurd_extreme_comparisons)]
8147 #[allow(unused_comparisons)]
8148 if __tmp.remaining() < Self::ENCODED_LEN {
8149 panic!(
8150 "buffer is too small (need {} bytes, but got {})",
8151 Self::ENCODED_LEN,
8152 __tmp.remaining(),
8153 )
8154 }
8155 __tmp.put_u32_le(self.custom_mode);
8156 __tmp.put_u32_le(self.properties.bits() as u32);
8157 __tmp.put_u8(self.number_modes);
8158 __tmp.put_u8(self.mode_index);
8159 __tmp.put_u8(self.standard_mode as u8);
8160 for val in &self.mode_name {
8161 __tmp.put_u8(*val);
8162 }
8163 if matches!(version, MavlinkVersion::V2) {
8164 let len = __tmp.len();
8165 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8166 } else {
8167 __tmp.len()
8168 }
8169 }
8170}
8171#[doc = "A change to the sequence number indicates that the set of AVAILABLE_MODES has changed. A receiver must re-request all available modes whenever the sequence number changes. This is only emitted after the first change and should then be broadcast at low rate (nominally 0.3 Hz) and on change. See <https://mavlink.io/en/services/standard_modes.html>."]
8172#[doc = ""]
8173#[doc = "ID: 437"]
8174#[derive(Debug, Clone, PartialEq)]
8175#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8176#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8177#[cfg_attr(feature = "ts", derive(TS))]
8178#[cfg_attr(feature = "ts", ts(export))]
8179pub struct AVAILABLE_MODES_MONITOR_DATA {
8180 #[doc = "Sequence number. The value iterates sequentially whenever AVAILABLE_MODES changes (e.g. support for a new mode is added/removed dynamically)."]
8181 pub seq: u8,
8182}
8183impl AVAILABLE_MODES_MONITOR_DATA {
8184 pub const ENCODED_LEN: usize = 1usize;
8185 pub const DEFAULT: Self = Self { seq: 0_u8 };
8186 #[cfg(feature = "arbitrary")]
8187 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8188 use arbitrary::{Arbitrary, Unstructured};
8189 let mut buf = [0u8; 1024];
8190 rng.fill_bytes(&mut buf);
8191 let mut unstructured = Unstructured::new(&buf);
8192 Self::arbitrary(&mut unstructured).unwrap_or_default()
8193 }
8194}
8195impl Default for AVAILABLE_MODES_MONITOR_DATA {
8196 fn default() -> Self {
8197 Self::DEFAULT.clone()
8198 }
8199}
8200impl MessageData for AVAILABLE_MODES_MONITOR_DATA {
8201 type Message = MavMessage;
8202 const ID: u32 = 437u32;
8203 const NAME: &'static str = "AVAILABLE_MODES_MONITOR";
8204 const EXTRA_CRC: u8 = 30u8;
8205 const ENCODED_LEN: usize = 1usize;
8206 fn deser(
8207 _version: MavlinkVersion,
8208 __input: &[u8],
8209 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8210 let avail_len = __input.len();
8211 let mut payload_buf = [0; Self::ENCODED_LEN];
8212 let mut buf = if avail_len < Self::ENCODED_LEN {
8213 payload_buf[0..avail_len].copy_from_slice(__input);
8214 Bytes::new(&payload_buf)
8215 } else {
8216 Bytes::new(__input)
8217 };
8218 let mut __struct = Self::default();
8219 __struct.seq = buf.get_u8()?;
8220 Ok(__struct)
8221 }
8222 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8223 let mut __tmp = BytesMut::new(bytes);
8224 #[allow(clippy::absurd_extreme_comparisons)]
8225 #[allow(unused_comparisons)]
8226 if __tmp.remaining() < Self::ENCODED_LEN {
8227 panic!(
8228 "buffer is too small (need {} bytes, but got {})",
8229 Self::ENCODED_LEN,
8230 __tmp.remaining(),
8231 )
8232 }
8233 __tmp.put_u8(self.seq);
8234 if matches!(version, MavlinkVersion::V2) {
8235 let len = __tmp.len();
8236 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8237 } else {
8238 __tmp.len()
8239 }
8240 }
8241}
8242#[doc = "Battery information that is static, or requires infrequent update. This message should requested using MAV_CMD_REQUEST_MESSAGE and/or streamed at very low rate. BATTERY_STATUS_V2 is used for higher-rate battery status information."]
8243#[doc = ""]
8244#[doc = "ID: 372"]
8245#[derive(Debug, Clone, PartialEq)]
8246#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8247#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8248#[cfg_attr(feature = "ts", derive(TS))]
8249#[cfg_attr(feature = "ts", ts(export))]
8250pub struct BATTERY_INFO_DATA {
8251 #[doc = "Minimum per-cell voltage when discharging. 0: field not provided."]
8252 pub discharge_minimum_voltage: f32,
8253 #[doc = "Minimum per-cell voltage when charging. 0: field not provided."]
8254 pub charging_minimum_voltage: f32,
8255 #[doc = "Minimum per-cell voltage when resting. 0: field not provided."]
8256 pub resting_minimum_voltage: f32,
8257 #[doc = "Maximum per-cell voltage when charged. 0: field not provided."]
8258 pub charging_maximum_voltage: f32,
8259 #[doc = "Maximum pack continuous charge current. 0: field not provided."]
8260 pub charging_maximum_current: f32,
8261 #[doc = "Battery nominal voltage. Used for conversion between Wh and Ah. 0: field not provided."]
8262 pub nominal_voltage: f32,
8263 #[doc = "Maximum pack discharge current. 0: field not provided."]
8264 pub discharge_maximum_current: f32,
8265 #[doc = "Maximum pack discharge burst current. 0: field not provided."]
8266 pub discharge_maximum_burst_current: f32,
8267 #[doc = "Fully charged design capacity. 0: field not provided."]
8268 pub design_capacity: f32,
8269 #[doc = "Predicted battery capacity when fully charged (accounting for battery degradation). NAN: field not provided."]
8270 pub full_charge_capacity: f32,
8271 #[doc = "Lifetime count of the number of charge/discharge cycles (<https://en.wikipedia.org/wiki/Charge_cycle>). UINT16_MAX: field not provided."]
8272 pub cycle_count: u16,
8273 #[doc = "Battery weight. 0: field not provided."]
8274 pub weight: u16,
8275 #[doc = "Battery ID"]
8276 pub id: u8,
8277 #[doc = "Function of the battery."]
8278 pub battery_function: MavBatteryFunction,
8279 #[doc = "Type (chemistry) of the battery."]
8280 pub mavtype: MavBatteryType,
8281 #[doc = "State of Health (SOH) estimate. Typically 100% at the time of manufacture and will decrease over time and use. -1: field not provided."]
8282 pub state_of_health: u8,
8283 #[doc = "Number of battery cells in series. 0: field not provided."]
8284 pub cells_in_series: u8,
8285 #[doc = "Manufacture date (DDMMYYYY) in ASCII characters, 0 terminated. All 0: field not provided."]
8286 #[cfg_attr(feature = "ts", ts(type = "string"))]
8287 pub manufacture_date: CharArray<9>,
8288 #[doc = "Serial number in ASCII characters, 0 terminated. All 0: field not provided."]
8289 #[cfg_attr(feature = "ts", ts(type = "string"))]
8290 pub serial_number: CharArray<32>,
8291 #[doc = "Battery device name. Formatted as manufacturer name then product name, separated with an underscore (in ASCII characters), 0 terminated. All 0: field not provided."]
8292 #[cfg_attr(feature = "ts", ts(type = "string"))]
8293 pub name: CharArray<50>,
8294}
8295impl BATTERY_INFO_DATA {
8296 pub const ENCODED_LEN: usize = 140usize;
8297 pub const DEFAULT: Self = Self {
8298 discharge_minimum_voltage: 0.0_f32,
8299 charging_minimum_voltage: 0.0_f32,
8300 resting_minimum_voltage: 0.0_f32,
8301 charging_maximum_voltage: 0.0_f32,
8302 charging_maximum_current: 0.0_f32,
8303 nominal_voltage: 0.0_f32,
8304 discharge_maximum_current: 0.0_f32,
8305 discharge_maximum_burst_current: 0.0_f32,
8306 design_capacity: 0.0_f32,
8307 full_charge_capacity: 0.0_f32,
8308 cycle_count: 0_u16,
8309 weight: 0_u16,
8310 id: 0_u8,
8311 battery_function: MavBatteryFunction::DEFAULT,
8312 mavtype: MavBatteryType::DEFAULT,
8313 state_of_health: 0_u8,
8314 cells_in_series: 0_u8,
8315 manufacture_date: CharArray::new([0_u8; 9usize]),
8316 serial_number: CharArray::new([0_u8; 32usize]),
8317 name: CharArray::new([0_u8; 50usize]),
8318 };
8319 #[cfg(feature = "arbitrary")]
8320 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8321 use arbitrary::{Arbitrary, Unstructured};
8322 let mut buf = [0u8; 1024];
8323 rng.fill_bytes(&mut buf);
8324 let mut unstructured = Unstructured::new(&buf);
8325 Self::arbitrary(&mut unstructured).unwrap_or_default()
8326 }
8327}
8328impl Default for BATTERY_INFO_DATA {
8329 fn default() -> Self {
8330 Self::DEFAULT.clone()
8331 }
8332}
8333impl MessageData for BATTERY_INFO_DATA {
8334 type Message = MavMessage;
8335 const ID: u32 = 372u32;
8336 const NAME: &'static str = "BATTERY_INFO";
8337 const EXTRA_CRC: u8 = 26u8;
8338 const ENCODED_LEN: usize = 140usize;
8339 fn deser(
8340 _version: MavlinkVersion,
8341 __input: &[u8],
8342 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8343 let avail_len = __input.len();
8344 let mut payload_buf = [0; Self::ENCODED_LEN];
8345 let mut buf = if avail_len < Self::ENCODED_LEN {
8346 payload_buf[0..avail_len].copy_from_slice(__input);
8347 Bytes::new(&payload_buf)
8348 } else {
8349 Bytes::new(__input)
8350 };
8351 let mut __struct = Self::default();
8352 __struct.discharge_minimum_voltage = buf.get_f32_le()?;
8353 __struct.charging_minimum_voltage = buf.get_f32_le()?;
8354 __struct.resting_minimum_voltage = buf.get_f32_le()?;
8355 __struct.charging_maximum_voltage = buf.get_f32_le()?;
8356 __struct.charging_maximum_current = buf.get_f32_le()?;
8357 __struct.nominal_voltage = buf.get_f32_le()?;
8358 __struct.discharge_maximum_current = buf.get_f32_le()?;
8359 __struct.discharge_maximum_burst_current = buf.get_f32_le()?;
8360 __struct.design_capacity = buf.get_f32_le()?;
8361 __struct.full_charge_capacity = buf.get_f32_le()?;
8362 __struct.cycle_count = buf.get_u16_le()?;
8363 __struct.weight = buf.get_u16_le()?;
8364 __struct.id = buf.get_u8()?;
8365 let tmp = buf.get_u8()?;
8366 __struct.battery_function =
8367 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8368 enum_type: "MavBatteryFunction",
8369 value: tmp as u64,
8370 })?;
8371 let tmp = buf.get_u8()?;
8372 __struct.mavtype =
8373 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8374 enum_type: "MavBatteryType",
8375 value: tmp as u64,
8376 })?;
8377 __struct.state_of_health = buf.get_u8()?;
8378 __struct.cells_in_series = buf.get_u8()?;
8379 let mut tmp = [0_u8; 9usize];
8380 for v in &mut tmp {
8381 *v = buf.get_u8()?;
8382 }
8383 __struct.manufacture_date = CharArray::new(tmp);
8384 let mut tmp = [0_u8; 32usize];
8385 for v in &mut tmp {
8386 *v = buf.get_u8()?;
8387 }
8388 __struct.serial_number = CharArray::new(tmp);
8389 let mut tmp = [0_u8; 50usize];
8390 for v in &mut tmp {
8391 *v = buf.get_u8()?;
8392 }
8393 __struct.name = CharArray::new(tmp);
8394 Ok(__struct)
8395 }
8396 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8397 let mut __tmp = BytesMut::new(bytes);
8398 #[allow(clippy::absurd_extreme_comparisons)]
8399 #[allow(unused_comparisons)]
8400 if __tmp.remaining() < Self::ENCODED_LEN {
8401 panic!(
8402 "buffer is too small (need {} bytes, but got {})",
8403 Self::ENCODED_LEN,
8404 __tmp.remaining(),
8405 )
8406 }
8407 __tmp.put_f32_le(self.discharge_minimum_voltage);
8408 __tmp.put_f32_le(self.charging_minimum_voltage);
8409 __tmp.put_f32_le(self.resting_minimum_voltage);
8410 __tmp.put_f32_le(self.charging_maximum_voltage);
8411 __tmp.put_f32_le(self.charging_maximum_current);
8412 __tmp.put_f32_le(self.nominal_voltage);
8413 __tmp.put_f32_le(self.discharge_maximum_current);
8414 __tmp.put_f32_le(self.discharge_maximum_burst_current);
8415 __tmp.put_f32_le(self.design_capacity);
8416 __tmp.put_f32_le(self.full_charge_capacity);
8417 __tmp.put_u16_le(self.cycle_count);
8418 __tmp.put_u16_le(self.weight);
8419 __tmp.put_u8(self.id);
8420 __tmp.put_u8(self.battery_function as u8);
8421 __tmp.put_u8(self.mavtype as u8);
8422 __tmp.put_u8(self.state_of_health);
8423 __tmp.put_u8(self.cells_in_series);
8424 for val in &self.manufacture_date {
8425 __tmp.put_u8(*val);
8426 }
8427 for val in &self.serial_number {
8428 __tmp.put_u8(*val);
8429 }
8430 for val in &self.name {
8431 __tmp.put_u8(*val);
8432 }
8433 if matches!(version, MavlinkVersion::V2) {
8434 let len = __tmp.len();
8435 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8436 } else {
8437 __tmp.len()
8438 }
8439 }
8440}
8441#[doc = "Battery information. Updates GCS with flight controller battery status. Smart batteries also use this message, but may additionally send BATTERY_INFO."]
8442#[doc = ""]
8443#[doc = "ID: 147"]
8444#[derive(Debug, Clone, PartialEq)]
8445#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8446#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8447#[cfg_attr(feature = "ts", derive(TS))]
8448#[cfg_attr(feature = "ts", ts(export))]
8449pub struct BATTERY_STATUS_DATA {
8450 #[doc = "Consumed charge, -1: autopilot does not provide consumption estimate"]
8451 pub current_consumed: i32,
8452 #[doc = "Consumed energy, -1: autopilot does not provide energy consumption estimate"]
8453 pub energy_consumed: i32,
8454 #[doc = "Temperature of the battery. INT16_MAX for unknown temperature."]
8455 pub temperature: i16,
8456 #[doc = "Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1)."]
8457 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8458 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
8459 pub voltages: [u16; 10],
8460 #[doc = "Battery current, -1: autopilot does not measure the current"]
8461 pub current_battery: i16,
8462 #[doc = "Battery ID"]
8463 pub id: u8,
8464 #[doc = "Function of the battery"]
8465 pub battery_function: MavBatteryFunction,
8466 #[doc = "Type (chemistry) of the battery"]
8467 pub mavtype: MavBatteryType,
8468 #[doc = "Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery."]
8469 pub battery_remaining: i8,
8470 #[doc = "Remaining battery time, 0: autopilot does not provide remaining battery time estimate"]
8471 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
8472 pub time_remaining: i32,
8473 #[doc = "State for extent of discharge, provided by autopilot for warning or external reactions"]
8474 #[cfg_attr(feature = "serde", serde(default))]
8475 pub charge_state: MavBatteryChargeState,
8476 #[doc = "Battery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead."]
8477 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
8478 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8479 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
8480 pub voltages_ext: [u16; 4],
8481 #[doc = "Battery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode."]
8482 #[cfg_attr(feature = "serde", serde(default))]
8483 pub mode: MavBatteryMode,
8484 #[doc = "Fault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported)."]
8485 #[cfg_attr(feature = "serde", serde(default))]
8486 pub fault_bitmask: MavBatteryFault,
8487}
8488impl BATTERY_STATUS_DATA {
8489 pub const ENCODED_LEN: usize = 54usize;
8490 pub const DEFAULT: Self = Self {
8491 current_consumed: 0_i32,
8492 energy_consumed: 0_i32,
8493 temperature: 0_i16,
8494 voltages: [0_u16; 10usize],
8495 current_battery: 0_i16,
8496 id: 0_u8,
8497 battery_function: MavBatteryFunction::DEFAULT,
8498 mavtype: MavBatteryType::DEFAULT,
8499 battery_remaining: 0_i8,
8500 time_remaining: 0_i32,
8501 charge_state: MavBatteryChargeState::DEFAULT,
8502 voltages_ext: [0_u16; 4usize],
8503 mode: MavBatteryMode::DEFAULT,
8504 fault_bitmask: MavBatteryFault::DEFAULT,
8505 };
8506 #[cfg(feature = "arbitrary")]
8507 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8508 use arbitrary::{Arbitrary, Unstructured};
8509 let mut buf = [0u8; 1024];
8510 rng.fill_bytes(&mut buf);
8511 let mut unstructured = Unstructured::new(&buf);
8512 Self::arbitrary(&mut unstructured).unwrap_or_default()
8513 }
8514}
8515impl Default for BATTERY_STATUS_DATA {
8516 fn default() -> Self {
8517 Self::DEFAULT.clone()
8518 }
8519}
8520impl MessageData for BATTERY_STATUS_DATA {
8521 type Message = MavMessage;
8522 const ID: u32 = 147u32;
8523 const NAME: &'static str = "BATTERY_STATUS";
8524 const EXTRA_CRC: u8 = 154u8;
8525 const ENCODED_LEN: usize = 54usize;
8526 fn deser(
8527 _version: MavlinkVersion,
8528 __input: &[u8],
8529 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8530 let avail_len = __input.len();
8531 let mut payload_buf = [0; Self::ENCODED_LEN];
8532 let mut buf = if avail_len < Self::ENCODED_LEN {
8533 payload_buf[0..avail_len].copy_from_slice(__input);
8534 Bytes::new(&payload_buf)
8535 } else {
8536 Bytes::new(__input)
8537 };
8538 let mut __struct = Self::default();
8539 __struct.current_consumed = buf.get_i32_le()?;
8540 __struct.energy_consumed = buf.get_i32_le()?;
8541 __struct.temperature = buf.get_i16_le()?;
8542 for v in &mut __struct.voltages {
8543 let val = buf.get_u16_le()?;
8544 *v = val;
8545 }
8546 __struct.current_battery = buf.get_i16_le()?;
8547 __struct.id = buf.get_u8()?;
8548 let tmp = buf.get_u8()?;
8549 __struct.battery_function =
8550 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8551 enum_type: "MavBatteryFunction",
8552 value: tmp as u64,
8553 })?;
8554 let tmp = buf.get_u8()?;
8555 __struct.mavtype =
8556 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8557 enum_type: "MavBatteryType",
8558 value: tmp as u64,
8559 })?;
8560 __struct.battery_remaining = buf.get_i8()?;
8561 __struct.time_remaining = buf.get_i32_le()?;
8562 let tmp = buf.get_u8()?;
8563 __struct.charge_state =
8564 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8565 enum_type: "MavBatteryChargeState",
8566 value: tmp as u64,
8567 })?;
8568 for v in &mut __struct.voltages_ext {
8569 let val = buf.get_u16_le()?;
8570 *v = val;
8571 }
8572 let tmp = buf.get_u8()?;
8573 __struct.mode =
8574 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8575 enum_type: "MavBatteryMode",
8576 value: tmp as u64,
8577 })?;
8578 let tmp = buf.get_u32_le()?;
8579 __struct.fault_bitmask = MavBatteryFault::from_bits(
8580 tmp as <MavBatteryFault as Flags>::Bits,
8581 )
8582 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
8583 flag_type: "MavBatteryFault",
8584 value: tmp as u64,
8585 })?;
8586 Ok(__struct)
8587 }
8588 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8589 let mut __tmp = BytesMut::new(bytes);
8590 #[allow(clippy::absurd_extreme_comparisons)]
8591 #[allow(unused_comparisons)]
8592 if __tmp.remaining() < Self::ENCODED_LEN {
8593 panic!(
8594 "buffer is too small (need {} bytes, but got {})",
8595 Self::ENCODED_LEN,
8596 __tmp.remaining(),
8597 )
8598 }
8599 __tmp.put_i32_le(self.current_consumed);
8600 __tmp.put_i32_le(self.energy_consumed);
8601 __tmp.put_i16_le(self.temperature);
8602 for val in &self.voltages {
8603 __tmp.put_u16_le(*val);
8604 }
8605 __tmp.put_i16_le(self.current_battery);
8606 __tmp.put_u8(self.id);
8607 __tmp.put_u8(self.battery_function as u8);
8608 __tmp.put_u8(self.mavtype as u8);
8609 __tmp.put_i8(self.battery_remaining);
8610 if matches!(version, MavlinkVersion::V2) {
8611 __tmp.put_i32_le(self.time_remaining);
8612 __tmp.put_u8(self.charge_state as u8);
8613 for val in &self.voltages_ext {
8614 __tmp.put_u16_le(*val);
8615 }
8616 __tmp.put_u8(self.mode as u8);
8617 __tmp.put_u32_le(self.fault_bitmask.bits() as u32);
8618 let len = __tmp.len();
8619 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8620 } else {
8621 __tmp.len()
8622 }
8623 }
8624}
8625#[doc = "Report button state change."]
8626#[doc = ""]
8627#[doc = "ID: 257"]
8628#[derive(Debug, Clone, PartialEq)]
8629#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8630#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8631#[cfg_attr(feature = "ts", derive(TS))]
8632#[cfg_attr(feature = "ts", ts(export))]
8633pub struct BUTTON_CHANGE_DATA {
8634 #[doc = "Timestamp (time since system boot)."]
8635 pub time_boot_ms: u32,
8636 #[doc = "Time of last change of button state."]
8637 pub last_change_ms: u32,
8638 #[doc = "Bitmap for state of buttons."]
8639 pub state: u8,
8640}
8641impl BUTTON_CHANGE_DATA {
8642 pub const ENCODED_LEN: usize = 9usize;
8643 pub const DEFAULT: Self = Self {
8644 time_boot_ms: 0_u32,
8645 last_change_ms: 0_u32,
8646 state: 0_u8,
8647 };
8648 #[cfg(feature = "arbitrary")]
8649 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8650 use arbitrary::{Arbitrary, Unstructured};
8651 let mut buf = [0u8; 1024];
8652 rng.fill_bytes(&mut buf);
8653 let mut unstructured = Unstructured::new(&buf);
8654 Self::arbitrary(&mut unstructured).unwrap_or_default()
8655 }
8656}
8657impl Default for BUTTON_CHANGE_DATA {
8658 fn default() -> Self {
8659 Self::DEFAULT.clone()
8660 }
8661}
8662impl MessageData for BUTTON_CHANGE_DATA {
8663 type Message = MavMessage;
8664 const ID: u32 = 257u32;
8665 const NAME: &'static str = "BUTTON_CHANGE";
8666 const EXTRA_CRC: u8 = 131u8;
8667 const ENCODED_LEN: usize = 9usize;
8668 fn deser(
8669 _version: MavlinkVersion,
8670 __input: &[u8],
8671 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8672 let avail_len = __input.len();
8673 let mut payload_buf = [0; Self::ENCODED_LEN];
8674 let mut buf = if avail_len < Self::ENCODED_LEN {
8675 payload_buf[0..avail_len].copy_from_slice(__input);
8676 Bytes::new(&payload_buf)
8677 } else {
8678 Bytes::new(__input)
8679 };
8680 let mut __struct = Self::default();
8681 __struct.time_boot_ms = buf.get_u32_le()?;
8682 __struct.last_change_ms = buf.get_u32_le()?;
8683 __struct.state = buf.get_u8()?;
8684 Ok(__struct)
8685 }
8686 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8687 let mut __tmp = BytesMut::new(bytes);
8688 #[allow(clippy::absurd_extreme_comparisons)]
8689 #[allow(unused_comparisons)]
8690 if __tmp.remaining() < Self::ENCODED_LEN {
8691 panic!(
8692 "buffer is too small (need {} bytes, but got {})",
8693 Self::ENCODED_LEN,
8694 __tmp.remaining(),
8695 )
8696 }
8697 __tmp.put_u32_le(self.time_boot_ms);
8698 __tmp.put_u32_le(self.last_change_ms);
8699 __tmp.put_u8(self.state);
8700 if matches!(version, MavlinkVersion::V2) {
8701 let len = __tmp.len();
8702 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8703 } else {
8704 __tmp.len()
8705 }
8706 }
8707}
8708#[doc = "Information about the status of a capture. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
8709#[doc = ""]
8710#[doc = "ID: 262"]
8711#[derive(Debug, Clone, PartialEq)]
8712#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8713#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8714#[cfg_attr(feature = "ts", derive(TS))]
8715#[cfg_attr(feature = "ts", ts(export))]
8716pub struct CAMERA_CAPTURE_STATUS_DATA {
8717 #[doc = "Timestamp (time since system boot)."]
8718 pub time_boot_ms: u32,
8719 #[doc = "Image capture interval"]
8720 pub image_interval: f32,
8721 #[doc = "Elapsed time since recording started (0: Not supported/available). A GCS should compute recording time and use non-zero values of this field to correct any discrepancy."]
8722 pub recording_time_ms: u32,
8723 #[doc = "Available storage capacity."]
8724 pub available_capacity: f32,
8725 #[doc = "Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress)"]
8726 pub image_status: u8,
8727 #[doc = "Current status of video capturing (0: idle, 1: capture in progress)"]
8728 pub video_status: u8,
8729 #[doc = "Total number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT)."]
8730 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
8731 pub image_count: i32,
8732 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
8733 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
8734 pub camera_device_id: u8,
8735}
8736impl CAMERA_CAPTURE_STATUS_DATA {
8737 pub const ENCODED_LEN: usize = 23usize;
8738 pub const DEFAULT: Self = Self {
8739 time_boot_ms: 0_u32,
8740 image_interval: 0.0_f32,
8741 recording_time_ms: 0_u32,
8742 available_capacity: 0.0_f32,
8743 image_status: 0_u8,
8744 video_status: 0_u8,
8745 image_count: 0_i32,
8746 camera_device_id: 0_u8,
8747 };
8748 #[cfg(feature = "arbitrary")]
8749 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8750 use arbitrary::{Arbitrary, Unstructured};
8751 let mut buf = [0u8; 1024];
8752 rng.fill_bytes(&mut buf);
8753 let mut unstructured = Unstructured::new(&buf);
8754 Self::arbitrary(&mut unstructured).unwrap_or_default()
8755 }
8756}
8757impl Default for CAMERA_CAPTURE_STATUS_DATA {
8758 fn default() -> Self {
8759 Self::DEFAULT.clone()
8760 }
8761}
8762impl MessageData for CAMERA_CAPTURE_STATUS_DATA {
8763 type Message = MavMessage;
8764 const ID: u32 = 262u32;
8765 const NAME: &'static str = "CAMERA_CAPTURE_STATUS";
8766 const EXTRA_CRC: u8 = 12u8;
8767 const ENCODED_LEN: usize = 23usize;
8768 fn deser(
8769 _version: MavlinkVersion,
8770 __input: &[u8],
8771 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8772 let avail_len = __input.len();
8773 let mut payload_buf = [0; Self::ENCODED_LEN];
8774 let mut buf = if avail_len < Self::ENCODED_LEN {
8775 payload_buf[0..avail_len].copy_from_slice(__input);
8776 Bytes::new(&payload_buf)
8777 } else {
8778 Bytes::new(__input)
8779 };
8780 let mut __struct = Self::default();
8781 __struct.time_boot_ms = buf.get_u32_le()?;
8782 __struct.image_interval = buf.get_f32_le()?;
8783 __struct.recording_time_ms = buf.get_u32_le()?;
8784 __struct.available_capacity = buf.get_f32_le()?;
8785 __struct.image_status = buf.get_u8()?;
8786 __struct.video_status = buf.get_u8()?;
8787 __struct.image_count = buf.get_i32_le()?;
8788 __struct.camera_device_id = buf.get_u8()?;
8789 Ok(__struct)
8790 }
8791 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8792 let mut __tmp = BytesMut::new(bytes);
8793 #[allow(clippy::absurd_extreme_comparisons)]
8794 #[allow(unused_comparisons)]
8795 if __tmp.remaining() < Self::ENCODED_LEN {
8796 panic!(
8797 "buffer is too small (need {} bytes, but got {})",
8798 Self::ENCODED_LEN,
8799 __tmp.remaining(),
8800 )
8801 }
8802 __tmp.put_u32_le(self.time_boot_ms);
8803 __tmp.put_f32_le(self.image_interval);
8804 __tmp.put_u32_le(self.recording_time_ms);
8805 __tmp.put_f32_le(self.available_capacity);
8806 __tmp.put_u8(self.image_status);
8807 __tmp.put_u8(self.video_status);
8808 if matches!(version, MavlinkVersion::V2) {
8809 __tmp.put_i32_le(self.image_count);
8810 __tmp.put_u8(self.camera_device_id);
8811 let len = __tmp.len();
8812 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8813 } else {
8814 __tmp.len()
8815 }
8816 }
8817}
8818#[doc = "Information about the field of view of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
8819#[doc = ""]
8820#[doc = "ID: 271"]
8821#[derive(Debug, Clone, PartialEq)]
8822#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8823#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8824#[cfg_attr(feature = "ts", derive(TS))]
8825#[cfg_attr(feature = "ts", ts(export))]
8826pub struct CAMERA_FOV_STATUS_DATA {
8827 #[doc = "Timestamp (time since system boot)."]
8828 pub time_boot_ms: u32,
8829 #[doc = "Latitude of camera (INT32_MAX if unknown)."]
8830 pub lat_camera: i32,
8831 #[doc = "Longitude of camera (INT32_MAX if unknown)."]
8832 pub lon_camera: i32,
8833 #[doc = "Altitude (MSL) of camera (INT32_MAX if unknown)."]
8834 pub alt_camera: i32,
8835 #[doc = "Latitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon)."]
8836 pub lat_image: i32,
8837 #[doc = "Longitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon)."]
8838 pub lon_image: i32,
8839 #[doc = "Altitude (MSL) of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon)."]
8840 pub alt_image: i32,
8841 #[doc = "Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
8842 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8843 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
8844 pub q: [f32; 4],
8845 #[doc = "Horizontal field of view (NaN if unknown)."]
8846 pub hfov: f32,
8847 #[doc = "Vertical field of view (NaN if unknown)."]
8848 pub vfov: f32,
8849 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
8850 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
8851 pub camera_device_id: u8,
8852}
8853impl CAMERA_FOV_STATUS_DATA {
8854 pub const ENCODED_LEN: usize = 53usize;
8855 pub const DEFAULT: Self = Self {
8856 time_boot_ms: 0_u32,
8857 lat_camera: 0_i32,
8858 lon_camera: 0_i32,
8859 alt_camera: 0_i32,
8860 lat_image: 0_i32,
8861 lon_image: 0_i32,
8862 alt_image: 0_i32,
8863 q: [0.0_f32; 4usize],
8864 hfov: 0.0_f32,
8865 vfov: 0.0_f32,
8866 camera_device_id: 0_u8,
8867 };
8868 #[cfg(feature = "arbitrary")]
8869 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8870 use arbitrary::{Arbitrary, Unstructured};
8871 let mut buf = [0u8; 1024];
8872 rng.fill_bytes(&mut buf);
8873 let mut unstructured = Unstructured::new(&buf);
8874 Self::arbitrary(&mut unstructured).unwrap_or_default()
8875 }
8876}
8877impl Default for CAMERA_FOV_STATUS_DATA {
8878 fn default() -> Self {
8879 Self::DEFAULT.clone()
8880 }
8881}
8882impl MessageData for CAMERA_FOV_STATUS_DATA {
8883 type Message = MavMessage;
8884 const ID: u32 = 271u32;
8885 const NAME: &'static str = "CAMERA_FOV_STATUS";
8886 const EXTRA_CRC: u8 = 22u8;
8887 const ENCODED_LEN: usize = 53usize;
8888 fn deser(
8889 _version: MavlinkVersion,
8890 __input: &[u8],
8891 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8892 let avail_len = __input.len();
8893 let mut payload_buf = [0; Self::ENCODED_LEN];
8894 let mut buf = if avail_len < Self::ENCODED_LEN {
8895 payload_buf[0..avail_len].copy_from_slice(__input);
8896 Bytes::new(&payload_buf)
8897 } else {
8898 Bytes::new(__input)
8899 };
8900 let mut __struct = Self::default();
8901 __struct.time_boot_ms = buf.get_u32_le()?;
8902 __struct.lat_camera = buf.get_i32_le()?;
8903 __struct.lon_camera = buf.get_i32_le()?;
8904 __struct.alt_camera = buf.get_i32_le()?;
8905 __struct.lat_image = buf.get_i32_le()?;
8906 __struct.lon_image = buf.get_i32_le()?;
8907 __struct.alt_image = buf.get_i32_le()?;
8908 for v in &mut __struct.q {
8909 let val = buf.get_f32_le()?;
8910 *v = val;
8911 }
8912 __struct.hfov = buf.get_f32_le()?;
8913 __struct.vfov = buf.get_f32_le()?;
8914 __struct.camera_device_id = buf.get_u8()?;
8915 Ok(__struct)
8916 }
8917 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8918 let mut __tmp = BytesMut::new(bytes);
8919 #[allow(clippy::absurd_extreme_comparisons)]
8920 #[allow(unused_comparisons)]
8921 if __tmp.remaining() < Self::ENCODED_LEN {
8922 panic!(
8923 "buffer is too small (need {} bytes, but got {})",
8924 Self::ENCODED_LEN,
8925 __tmp.remaining(),
8926 )
8927 }
8928 __tmp.put_u32_le(self.time_boot_ms);
8929 __tmp.put_i32_le(self.lat_camera);
8930 __tmp.put_i32_le(self.lon_camera);
8931 __tmp.put_i32_le(self.alt_camera);
8932 __tmp.put_i32_le(self.lat_image);
8933 __tmp.put_i32_le(self.lon_image);
8934 __tmp.put_i32_le(self.alt_image);
8935 for val in &self.q {
8936 __tmp.put_f32_le(*val);
8937 }
8938 __tmp.put_f32_le(self.hfov);
8939 __tmp.put_f32_le(self.vfov);
8940 if matches!(version, MavlinkVersion::V2) {
8941 __tmp.put_u8(self.camera_device_id);
8942 let len = __tmp.len();
8943 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8944 } else {
8945 __tmp.len()
8946 }
8947 }
8948}
8949#[doc = "Information about a captured image. This is emitted every time a message is captured. MAV_CMD_REQUEST_MESSAGE can be used to (re)request this message for a specific sequence number or range of sequence numbers: MAV_CMD_REQUEST_MESSAGE.param2 indicates the sequence number the first image to send, or set to -1 to send the message for all sequence numbers. MAV_CMD_REQUEST_MESSAGE.param3 is used to specify a range of messages to send: set to 0 (default) to send just the the message for the sequence number in param 2, set to -1 to send the message for the sequence number in param 2 and all the following sequence numbers, set to the sequence number of the final message in the range."]
8950#[doc = ""]
8951#[doc = "ID: 263"]
8952#[derive(Debug, Clone, PartialEq)]
8953#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8954#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8955#[cfg_attr(feature = "ts", derive(TS))]
8956#[cfg_attr(feature = "ts", ts(export))]
8957pub struct CAMERA_IMAGE_CAPTURED_DATA {
8958 #[doc = "Timestamp (time since UNIX epoch) in UTC. 0 for unknown."]
8959 pub time_utc: u64,
8960 #[doc = "Timestamp (time since system boot)."]
8961 pub time_boot_ms: u32,
8962 #[doc = "Latitude where image was taken"]
8963 pub lat: i32,
8964 #[doc = "Longitude where capture was taken"]
8965 pub lon: i32,
8966 #[doc = "Altitude (MSL) where image was taken"]
8967 pub alt: i32,
8968 #[doc = "Altitude above ground"]
8969 pub relative_alt: i32,
8970 #[doc = "Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
8971 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8972 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
8973 pub q: [f32; 4],
8974 #[doc = "Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1)"]
8975 pub image_index: i32,
8976 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id). Field name is usually camera_device_id."]
8977 pub camera_id: u8,
8978 #[doc = "Boolean indicating success (1) or failure (0) while capturing this image."]
8979 pub capture_result: i8,
8980 #[doc = "URL of image taken. Either local storage or <http://foo.jpg> if camera provides an HTTP interface."]
8981 #[cfg_attr(feature = "ts", ts(type = "string"))]
8982 pub file_url: CharArray<205>,
8983}
8984impl CAMERA_IMAGE_CAPTURED_DATA {
8985 pub const ENCODED_LEN: usize = 255usize;
8986 pub const DEFAULT: Self = Self {
8987 time_utc: 0_u64,
8988 time_boot_ms: 0_u32,
8989 lat: 0_i32,
8990 lon: 0_i32,
8991 alt: 0_i32,
8992 relative_alt: 0_i32,
8993 q: [0.0_f32; 4usize],
8994 image_index: 0_i32,
8995 camera_id: 0_u8,
8996 capture_result: 0_i8,
8997 file_url: CharArray::new([0_u8; 205usize]),
8998 };
8999 #[cfg(feature = "arbitrary")]
9000 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9001 use arbitrary::{Arbitrary, Unstructured};
9002 let mut buf = [0u8; 1024];
9003 rng.fill_bytes(&mut buf);
9004 let mut unstructured = Unstructured::new(&buf);
9005 Self::arbitrary(&mut unstructured).unwrap_or_default()
9006 }
9007}
9008impl Default for CAMERA_IMAGE_CAPTURED_DATA {
9009 fn default() -> Self {
9010 Self::DEFAULT.clone()
9011 }
9012}
9013impl MessageData for CAMERA_IMAGE_CAPTURED_DATA {
9014 type Message = MavMessage;
9015 const ID: u32 = 263u32;
9016 const NAME: &'static str = "CAMERA_IMAGE_CAPTURED";
9017 const EXTRA_CRC: u8 = 133u8;
9018 const ENCODED_LEN: usize = 255usize;
9019 fn deser(
9020 _version: MavlinkVersion,
9021 __input: &[u8],
9022 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9023 let avail_len = __input.len();
9024 let mut payload_buf = [0; Self::ENCODED_LEN];
9025 let mut buf = if avail_len < Self::ENCODED_LEN {
9026 payload_buf[0..avail_len].copy_from_slice(__input);
9027 Bytes::new(&payload_buf)
9028 } else {
9029 Bytes::new(__input)
9030 };
9031 let mut __struct = Self::default();
9032 __struct.time_utc = buf.get_u64_le()?;
9033 __struct.time_boot_ms = buf.get_u32_le()?;
9034 __struct.lat = buf.get_i32_le()?;
9035 __struct.lon = buf.get_i32_le()?;
9036 __struct.alt = buf.get_i32_le()?;
9037 __struct.relative_alt = buf.get_i32_le()?;
9038 for v in &mut __struct.q {
9039 let val = buf.get_f32_le()?;
9040 *v = val;
9041 }
9042 __struct.image_index = buf.get_i32_le()?;
9043 __struct.camera_id = buf.get_u8()?;
9044 __struct.capture_result = buf.get_i8()?;
9045 let mut tmp = [0_u8; 205usize];
9046 for v in &mut tmp {
9047 *v = buf.get_u8()?;
9048 }
9049 __struct.file_url = CharArray::new(tmp);
9050 Ok(__struct)
9051 }
9052 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9053 let mut __tmp = BytesMut::new(bytes);
9054 #[allow(clippy::absurd_extreme_comparisons)]
9055 #[allow(unused_comparisons)]
9056 if __tmp.remaining() < Self::ENCODED_LEN {
9057 panic!(
9058 "buffer is too small (need {} bytes, but got {})",
9059 Self::ENCODED_LEN,
9060 __tmp.remaining(),
9061 )
9062 }
9063 __tmp.put_u64_le(self.time_utc);
9064 __tmp.put_u32_le(self.time_boot_ms);
9065 __tmp.put_i32_le(self.lat);
9066 __tmp.put_i32_le(self.lon);
9067 __tmp.put_i32_le(self.alt);
9068 __tmp.put_i32_le(self.relative_alt);
9069 for val in &self.q {
9070 __tmp.put_f32_le(*val);
9071 }
9072 __tmp.put_i32_le(self.image_index);
9073 __tmp.put_u8(self.camera_id);
9074 __tmp.put_i8(self.capture_result);
9075 for val in &self.file_url {
9076 __tmp.put_u8(*val);
9077 }
9078 if matches!(version, MavlinkVersion::V2) {
9079 let len = __tmp.len();
9080 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9081 } else {
9082 __tmp.len()
9083 }
9084 }
9085}
9086#[doc = "Information about a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
9087#[doc = ""]
9088#[doc = "ID: 259"]
9089#[derive(Debug, Clone, PartialEq)]
9090#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9091#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9092#[cfg_attr(feature = "ts", derive(TS))]
9093#[cfg_attr(feature = "ts", ts(export))]
9094pub struct CAMERA_INFORMATION_DATA {
9095 #[doc = "Timestamp (time since system boot)."]
9096 pub time_boot_ms: u32,
9097 #[doc = "Version of the camera firmware, encoded as: (Dev&0xff)<<24 | (Patch&0xff)<<16 | (Minor&0xff)<<8 | (Major&0xff). Use 0 if not known."]
9098 pub firmware_version: u32,
9099 #[doc = "Focal length. Use NaN if not known."]
9100 pub focal_length: f32,
9101 #[doc = "Image sensor size horizontal. Use NaN if not known."]
9102 pub sensor_size_h: f32,
9103 #[doc = "Image sensor size vertical. Use NaN if not known."]
9104 pub sensor_size_v: f32,
9105 #[doc = "Bitmap of camera capability flags."]
9106 pub flags: CameraCapFlags,
9107 #[doc = "Horizontal image resolution. Use 0 if not known."]
9108 pub resolution_h: u16,
9109 #[doc = "Vertical image resolution. Use 0 if not known."]
9110 pub resolution_v: u16,
9111 #[doc = "Camera definition version (iteration). Use 0 if not known."]
9112 pub cam_definition_version: u16,
9113 #[doc = "Name of the camera vendor"]
9114 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9115 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
9116 pub vendor_name: [u8; 32],
9117 #[doc = "Name of the camera model"]
9118 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9119 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
9120 pub model_name: [u8; 32],
9121 #[doc = "Reserved for a lens ID. Use 0 if not known."]
9122 pub lens_id: u8,
9123 #[doc = "Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated. Use a zero-length string if not known."]
9124 #[cfg_attr(feature = "ts", ts(type = "string"))]
9125 pub cam_definition_uri: CharArray<140>,
9126 #[doc = "Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera."]
9127 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
9128 pub gimbal_device_id: u8,
9129 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
9130 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
9131 pub camera_device_id: u8,
9132}
9133impl CAMERA_INFORMATION_DATA {
9134 pub const ENCODED_LEN: usize = 237usize;
9135 pub const DEFAULT: Self = Self {
9136 time_boot_ms: 0_u32,
9137 firmware_version: 0_u32,
9138 focal_length: 0.0_f32,
9139 sensor_size_h: 0.0_f32,
9140 sensor_size_v: 0.0_f32,
9141 flags: CameraCapFlags::DEFAULT,
9142 resolution_h: 0_u16,
9143 resolution_v: 0_u16,
9144 cam_definition_version: 0_u16,
9145 vendor_name: [0_u8; 32usize],
9146 model_name: [0_u8; 32usize],
9147 lens_id: 0_u8,
9148 cam_definition_uri: CharArray::new([0_u8; 140usize]),
9149 gimbal_device_id: 0_u8,
9150 camera_device_id: 0_u8,
9151 };
9152 #[cfg(feature = "arbitrary")]
9153 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9154 use arbitrary::{Arbitrary, Unstructured};
9155 let mut buf = [0u8; 1024];
9156 rng.fill_bytes(&mut buf);
9157 let mut unstructured = Unstructured::new(&buf);
9158 Self::arbitrary(&mut unstructured).unwrap_or_default()
9159 }
9160}
9161impl Default for CAMERA_INFORMATION_DATA {
9162 fn default() -> Self {
9163 Self::DEFAULT.clone()
9164 }
9165}
9166impl MessageData for CAMERA_INFORMATION_DATA {
9167 type Message = MavMessage;
9168 const ID: u32 = 259u32;
9169 const NAME: &'static str = "CAMERA_INFORMATION";
9170 const EXTRA_CRC: u8 = 92u8;
9171 const ENCODED_LEN: usize = 237usize;
9172 fn deser(
9173 _version: MavlinkVersion,
9174 __input: &[u8],
9175 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9176 let avail_len = __input.len();
9177 let mut payload_buf = [0; Self::ENCODED_LEN];
9178 let mut buf = if avail_len < Self::ENCODED_LEN {
9179 payload_buf[0..avail_len].copy_from_slice(__input);
9180 Bytes::new(&payload_buf)
9181 } else {
9182 Bytes::new(__input)
9183 };
9184 let mut __struct = Self::default();
9185 __struct.time_boot_ms = buf.get_u32_le()?;
9186 __struct.firmware_version = buf.get_u32_le()?;
9187 __struct.focal_length = buf.get_f32_le()?;
9188 __struct.sensor_size_h = buf.get_f32_le()?;
9189 __struct.sensor_size_v = buf.get_f32_le()?;
9190 let tmp = buf.get_u32_le()?;
9191 __struct.flags = CameraCapFlags::from_bits(tmp as <CameraCapFlags as Flags>::Bits).ok_or(
9192 ::mavlink_core::error::ParserError::InvalidFlag {
9193 flag_type: "CameraCapFlags",
9194 value: tmp as u64,
9195 },
9196 )?;
9197 __struct.resolution_h = buf.get_u16_le()?;
9198 __struct.resolution_v = buf.get_u16_le()?;
9199 __struct.cam_definition_version = buf.get_u16_le()?;
9200 for v in &mut __struct.vendor_name {
9201 let val = buf.get_u8()?;
9202 *v = val;
9203 }
9204 for v in &mut __struct.model_name {
9205 let val = buf.get_u8()?;
9206 *v = val;
9207 }
9208 __struct.lens_id = buf.get_u8()?;
9209 let mut tmp = [0_u8; 140usize];
9210 for v in &mut tmp {
9211 *v = buf.get_u8()?;
9212 }
9213 __struct.cam_definition_uri = CharArray::new(tmp);
9214 __struct.gimbal_device_id = buf.get_u8()?;
9215 __struct.camera_device_id = buf.get_u8()?;
9216 Ok(__struct)
9217 }
9218 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9219 let mut __tmp = BytesMut::new(bytes);
9220 #[allow(clippy::absurd_extreme_comparisons)]
9221 #[allow(unused_comparisons)]
9222 if __tmp.remaining() < Self::ENCODED_LEN {
9223 panic!(
9224 "buffer is too small (need {} bytes, but got {})",
9225 Self::ENCODED_LEN,
9226 __tmp.remaining(),
9227 )
9228 }
9229 __tmp.put_u32_le(self.time_boot_ms);
9230 __tmp.put_u32_le(self.firmware_version);
9231 __tmp.put_f32_le(self.focal_length);
9232 __tmp.put_f32_le(self.sensor_size_h);
9233 __tmp.put_f32_le(self.sensor_size_v);
9234 __tmp.put_u32_le(self.flags.bits() as u32);
9235 __tmp.put_u16_le(self.resolution_h);
9236 __tmp.put_u16_le(self.resolution_v);
9237 __tmp.put_u16_le(self.cam_definition_version);
9238 for val in &self.vendor_name {
9239 __tmp.put_u8(*val);
9240 }
9241 for val in &self.model_name {
9242 __tmp.put_u8(*val);
9243 }
9244 __tmp.put_u8(self.lens_id);
9245 for val in &self.cam_definition_uri {
9246 __tmp.put_u8(*val);
9247 }
9248 if matches!(version, MavlinkVersion::V2) {
9249 __tmp.put_u8(self.gimbal_device_id);
9250 __tmp.put_u8(self.camera_device_id);
9251 let len = __tmp.len();
9252 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9253 } else {
9254 __tmp.len()
9255 }
9256 }
9257}
9258#[doc = "Settings of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
9259#[doc = ""]
9260#[doc = "ID: 260"]
9261#[derive(Debug, Clone, PartialEq)]
9262#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9263#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9264#[cfg_attr(feature = "ts", derive(TS))]
9265#[cfg_attr(feature = "ts", ts(export))]
9266pub struct CAMERA_SETTINGS_DATA {
9267 #[doc = "Timestamp (time since system boot)."]
9268 pub time_boot_ms: u32,
9269 #[doc = "Camera mode"]
9270 pub mode_id: CameraMode,
9271 #[doc = "Current zoom level as a percentage of the full range (0.0 to 100.0, NaN if not known)"]
9272 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
9273 pub zoomLevel: f32,
9274 #[doc = "Current focus level as a percentage of the full range (0.0 to 100.0, NaN if not known)"]
9275 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
9276 pub focusLevel: f32,
9277 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
9278 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
9279 pub camera_device_id: u8,
9280}
9281impl CAMERA_SETTINGS_DATA {
9282 pub const ENCODED_LEN: usize = 14usize;
9283 pub const DEFAULT: Self = Self {
9284 time_boot_ms: 0_u32,
9285 mode_id: CameraMode::DEFAULT,
9286 zoomLevel: 0.0_f32,
9287 focusLevel: 0.0_f32,
9288 camera_device_id: 0_u8,
9289 };
9290 #[cfg(feature = "arbitrary")]
9291 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9292 use arbitrary::{Arbitrary, Unstructured};
9293 let mut buf = [0u8; 1024];
9294 rng.fill_bytes(&mut buf);
9295 let mut unstructured = Unstructured::new(&buf);
9296 Self::arbitrary(&mut unstructured).unwrap_or_default()
9297 }
9298}
9299impl Default for CAMERA_SETTINGS_DATA {
9300 fn default() -> Self {
9301 Self::DEFAULT.clone()
9302 }
9303}
9304impl MessageData for CAMERA_SETTINGS_DATA {
9305 type Message = MavMessage;
9306 const ID: u32 = 260u32;
9307 const NAME: &'static str = "CAMERA_SETTINGS";
9308 const EXTRA_CRC: u8 = 146u8;
9309 const ENCODED_LEN: usize = 14usize;
9310 fn deser(
9311 _version: MavlinkVersion,
9312 __input: &[u8],
9313 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9314 let avail_len = __input.len();
9315 let mut payload_buf = [0; Self::ENCODED_LEN];
9316 let mut buf = if avail_len < Self::ENCODED_LEN {
9317 payload_buf[0..avail_len].copy_from_slice(__input);
9318 Bytes::new(&payload_buf)
9319 } else {
9320 Bytes::new(__input)
9321 };
9322 let mut __struct = Self::default();
9323 __struct.time_boot_ms = buf.get_u32_le()?;
9324 let tmp = buf.get_u8()?;
9325 __struct.mode_id =
9326 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9327 enum_type: "CameraMode",
9328 value: tmp as u64,
9329 })?;
9330 __struct.zoomLevel = buf.get_f32_le()?;
9331 __struct.focusLevel = buf.get_f32_le()?;
9332 __struct.camera_device_id = buf.get_u8()?;
9333 Ok(__struct)
9334 }
9335 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9336 let mut __tmp = BytesMut::new(bytes);
9337 #[allow(clippy::absurd_extreme_comparisons)]
9338 #[allow(unused_comparisons)]
9339 if __tmp.remaining() < Self::ENCODED_LEN {
9340 panic!(
9341 "buffer is too small (need {} bytes, but got {})",
9342 Self::ENCODED_LEN,
9343 __tmp.remaining(),
9344 )
9345 }
9346 __tmp.put_u32_le(self.time_boot_ms);
9347 __tmp.put_u8(self.mode_id as u8);
9348 if matches!(version, MavlinkVersion::V2) {
9349 __tmp.put_f32_le(self.zoomLevel);
9350 __tmp.put_f32_le(self.focusLevel);
9351 __tmp.put_u8(self.camera_device_id);
9352 let len = __tmp.len();
9353 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9354 } else {
9355 __tmp.len()
9356 }
9357 }
9358}
9359#[doc = "Camera absolute thermal range. This can be streamed when the associated VIDEO_STREAM_STATUS `flag` field bit VIDEO_STREAM_STATUS_FLAGS_THERMAL_RANGE_ENABLED is set, but a GCS may choose to only request it for the current active stream. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval (param3 indicates the stream id of the current camera, or 0 for all streams, param4 indicates the target camera_device_id for autopilot-attached cameras or 0 for MAVLink cameras)."]
9360#[doc = ""]
9361#[doc = "ID: 277"]
9362#[derive(Debug, Clone, PartialEq)]
9363#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9364#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9365#[cfg_attr(feature = "ts", derive(TS))]
9366#[cfg_attr(feature = "ts", ts(export))]
9367pub struct CAMERA_THERMAL_RANGE_DATA {
9368 #[doc = "Timestamp (time since system boot)."]
9369 pub time_boot_ms: u32,
9370 #[doc = "Temperature max."]
9371 pub max: f32,
9372 #[doc = "Temperature max point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown."]
9373 pub max_point_x: f32,
9374 #[doc = "Temperature max point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown."]
9375 pub max_point_y: f32,
9376 #[doc = "Temperature min."]
9377 pub min: f32,
9378 #[doc = "Temperature min point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown."]
9379 pub min_point_x: f32,
9380 #[doc = "Temperature min point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown."]
9381 pub min_point_y: f32,
9382 #[doc = "Video Stream ID (1 for first, 2 for second, etc.)"]
9383 pub stream_id: u8,
9384 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
9385 pub camera_device_id: u8,
9386}
9387impl CAMERA_THERMAL_RANGE_DATA {
9388 pub const ENCODED_LEN: usize = 30usize;
9389 pub const DEFAULT: Self = Self {
9390 time_boot_ms: 0_u32,
9391 max: 0.0_f32,
9392 max_point_x: 0.0_f32,
9393 max_point_y: 0.0_f32,
9394 min: 0.0_f32,
9395 min_point_x: 0.0_f32,
9396 min_point_y: 0.0_f32,
9397 stream_id: 0_u8,
9398 camera_device_id: 0_u8,
9399 };
9400 #[cfg(feature = "arbitrary")]
9401 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9402 use arbitrary::{Arbitrary, Unstructured};
9403 let mut buf = [0u8; 1024];
9404 rng.fill_bytes(&mut buf);
9405 let mut unstructured = Unstructured::new(&buf);
9406 Self::arbitrary(&mut unstructured).unwrap_or_default()
9407 }
9408}
9409impl Default for CAMERA_THERMAL_RANGE_DATA {
9410 fn default() -> Self {
9411 Self::DEFAULT.clone()
9412 }
9413}
9414impl MessageData for CAMERA_THERMAL_RANGE_DATA {
9415 type Message = MavMessage;
9416 const ID: u32 = 277u32;
9417 const NAME: &'static str = "CAMERA_THERMAL_RANGE";
9418 const EXTRA_CRC: u8 = 62u8;
9419 const ENCODED_LEN: usize = 30usize;
9420 fn deser(
9421 _version: MavlinkVersion,
9422 __input: &[u8],
9423 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9424 let avail_len = __input.len();
9425 let mut payload_buf = [0; Self::ENCODED_LEN];
9426 let mut buf = if avail_len < Self::ENCODED_LEN {
9427 payload_buf[0..avail_len].copy_from_slice(__input);
9428 Bytes::new(&payload_buf)
9429 } else {
9430 Bytes::new(__input)
9431 };
9432 let mut __struct = Self::default();
9433 __struct.time_boot_ms = buf.get_u32_le()?;
9434 __struct.max = buf.get_f32_le()?;
9435 __struct.max_point_x = buf.get_f32_le()?;
9436 __struct.max_point_y = buf.get_f32_le()?;
9437 __struct.min = buf.get_f32_le()?;
9438 __struct.min_point_x = buf.get_f32_le()?;
9439 __struct.min_point_y = buf.get_f32_le()?;
9440 __struct.stream_id = buf.get_u8()?;
9441 __struct.camera_device_id = buf.get_u8()?;
9442 Ok(__struct)
9443 }
9444 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9445 let mut __tmp = BytesMut::new(bytes);
9446 #[allow(clippy::absurd_extreme_comparisons)]
9447 #[allow(unused_comparisons)]
9448 if __tmp.remaining() < Self::ENCODED_LEN {
9449 panic!(
9450 "buffer is too small (need {} bytes, but got {})",
9451 Self::ENCODED_LEN,
9452 __tmp.remaining(),
9453 )
9454 }
9455 __tmp.put_u32_le(self.time_boot_ms);
9456 __tmp.put_f32_le(self.max);
9457 __tmp.put_f32_le(self.max_point_x);
9458 __tmp.put_f32_le(self.max_point_y);
9459 __tmp.put_f32_le(self.min);
9460 __tmp.put_f32_le(self.min_point_x);
9461 __tmp.put_f32_le(self.min_point_y);
9462 __tmp.put_u8(self.stream_id);
9463 __tmp.put_u8(self.camera_device_id);
9464 if matches!(version, MavlinkVersion::V2) {
9465 let len = __tmp.len();
9466 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9467 } else {
9468 __tmp.len()
9469 }
9470 }
9471}
9472#[doc = "Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval."]
9473#[doc = ""]
9474#[doc = "ID: 276"]
9475#[derive(Debug, Clone, PartialEq)]
9476#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9477#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9478#[cfg_attr(feature = "ts", derive(TS))]
9479#[cfg_attr(feature = "ts", ts(export))]
9480pub struct CAMERA_TRACKING_GEO_STATUS_DATA {
9481 #[doc = "Latitude of tracked object"]
9482 pub lat: i32,
9483 #[doc = "Longitude of tracked object"]
9484 pub lon: i32,
9485 #[doc = "Altitude of tracked object(AMSL, WGS84)"]
9486 pub alt: f32,
9487 #[doc = "Horizontal accuracy. NAN if unknown"]
9488 pub h_acc: f32,
9489 #[doc = "Vertical accuracy. NAN if unknown"]
9490 pub v_acc: f32,
9491 #[doc = "North velocity of tracked object. NAN if unknown"]
9492 pub vel_n: f32,
9493 #[doc = "East velocity of tracked object. NAN if unknown"]
9494 pub vel_e: f32,
9495 #[doc = "Down velocity of tracked object. NAN if unknown"]
9496 pub vel_d: f32,
9497 #[doc = "Velocity accuracy. NAN if unknown"]
9498 pub vel_acc: f32,
9499 #[doc = "Distance between camera and tracked object. NAN if unknown"]
9500 pub dist: f32,
9501 #[doc = "Heading in radians, in NED. NAN if unknown"]
9502 pub hdg: f32,
9503 #[doc = "Accuracy of heading, in NED. NAN if unknown"]
9504 pub hdg_acc: f32,
9505 #[doc = "Current tracking status"]
9506 pub tracking_status: CameraTrackingStatusFlags,
9507 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
9508 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
9509 pub camera_device_id: u8,
9510}
9511impl CAMERA_TRACKING_GEO_STATUS_DATA {
9512 pub const ENCODED_LEN: usize = 50usize;
9513 pub const DEFAULT: Self = Self {
9514 lat: 0_i32,
9515 lon: 0_i32,
9516 alt: 0.0_f32,
9517 h_acc: 0.0_f32,
9518 v_acc: 0.0_f32,
9519 vel_n: 0.0_f32,
9520 vel_e: 0.0_f32,
9521 vel_d: 0.0_f32,
9522 vel_acc: 0.0_f32,
9523 dist: 0.0_f32,
9524 hdg: 0.0_f32,
9525 hdg_acc: 0.0_f32,
9526 tracking_status: CameraTrackingStatusFlags::DEFAULT,
9527 camera_device_id: 0_u8,
9528 };
9529 #[cfg(feature = "arbitrary")]
9530 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9531 use arbitrary::{Arbitrary, Unstructured};
9532 let mut buf = [0u8; 1024];
9533 rng.fill_bytes(&mut buf);
9534 let mut unstructured = Unstructured::new(&buf);
9535 Self::arbitrary(&mut unstructured).unwrap_or_default()
9536 }
9537}
9538impl Default for CAMERA_TRACKING_GEO_STATUS_DATA {
9539 fn default() -> Self {
9540 Self::DEFAULT.clone()
9541 }
9542}
9543impl MessageData for CAMERA_TRACKING_GEO_STATUS_DATA {
9544 type Message = MavMessage;
9545 const ID: u32 = 276u32;
9546 const NAME: &'static str = "CAMERA_TRACKING_GEO_STATUS";
9547 const EXTRA_CRC: u8 = 18u8;
9548 const ENCODED_LEN: usize = 50usize;
9549 fn deser(
9550 _version: MavlinkVersion,
9551 __input: &[u8],
9552 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9553 let avail_len = __input.len();
9554 let mut payload_buf = [0; Self::ENCODED_LEN];
9555 let mut buf = if avail_len < Self::ENCODED_LEN {
9556 payload_buf[0..avail_len].copy_from_slice(__input);
9557 Bytes::new(&payload_buf)
9558 } else {
9559 Bytes::new(__input)
9560 };
9561 let mut __struct = Self::default();
9562 __struct.lat = buf.get_i32_le()?;
9563 __struct.lon = buf.get_i32_le()?;
9564 __struct.alt = buf.get_f32_le()?;
9565 __struct.h_acc = buf.get_f32_le()?;
9566 __struct.v_acc = buf.get_f32_le()?;
9567 __struct.vel_n = buf.get_f32_le()?;
9568 __struct.vel_e = buf.get_f32_le()?;
9569 __struct.vel_d = buf.get_f32_le()?;
9570 __struct.vel_acc = buf.get_f32_le()?;
9571 __struct.dist = buf.get_f32_le()?;
9572 __struct.hdg = buf.get_f32_le()?;
9573 __struct.hdg_acc = buf.get_f32_le()?;
9574 let tmp = buf.get_u8()?;
9575 __struct.tracking_status =
9576 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9577 enum_type: "CameraTrackingStatusFlags",
9578 value: tmp as u64,
9579 })?;
9580 __struct.camera_device_id = buf.get_u8()?;
9581 Ok(__struct)
9582 }
9583 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9584 let mut __tmp = BytesMut::new(bytes);
9585 #[allow(clippy::absurd_extreme_comparisons)]
9586 #[allow(unused_comparisons)]
9587 if __tmp.remaining() < Self::ENCODED_LEN {
9588 panic!(
9589 "buffer is too small (need {} bytes, but got {})",
9590 Self::ENCODED_LEN,
9591 __tmp.remaining(),
9592 )
9593 }
9594 __tmp.put_i32_le(self.lat);
9595 __tmp.put_i32_le(self.lon);
9596 __tmp.put_f32_le(self.alt);
9597 __tmp.put_f32_le(self.h_acc);
9598 __tmp.put_f32_le(self.v_acc);
9599 __tmp.put_f32_le(self.vel_n);
9600 __tmp.put_f32_le(self.vel_e);
9601 __tmp.put_f32_le(self.vel_d);
9602 __tmp.put_f32_le(self.vel_acc);
9603 __tmp.put_f32_le(self.dist);
9604 __tmp.put_f32_le(self.hdg);
9605 __tmp.put_f32_le(self.hdg_acc);
9606 __tmp.put_u8(self.tracking_status as u8);
9607 if matches!(version, MavlinkVersion::V2) {
9608 __tmp.put_u8(self.camera_device_id);
9609 let len = __tmp.len();
9610 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9611 } else {
9612 __tmp.len()
9613 }
9614 }
9615}
9616#[doc = "Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval."]
9617#[doc = ""]
9618#[doc = "ID: 275"]
9619#[derive(Debug, Clone, PartialEq)]
9620#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9621#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9622#[cfg_attr(feature = "ts", derive(TS))]
9623#[cfg_attr(feature = "ts", ts(export))]
9624pub struct CAMERA_TRACKING_IMAGE_STATUS_DATA {
9625 #[doc = "Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown"]
9626 pub point_x: f32,
9627 #[doc = "Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown"]
9628 pub point_y: f32,
9629 #[doc = "Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown"]
9630 pub radius: f32,
9631 #[doc = "Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown"]
9632 pub rec_top_x: f32,
9633 #[doc = "Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown"]
9634 pub rec_top_y: f32,
9635 #[doc = "Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown"]
9636 pub rec_bottom_x: f32,
9637 #[doc = "Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown"]
9638 pub rec_bottom_y: f32,
9639 #[doc = "Current tracking status"]
9640 pub tracking_status: CameraTrackingStatusFlags,
9641 #[doc = "Current tracking mode"]
9642 pub tracking_mode: CameraTrackingMode,
9643 #[doc = "Defines location of target data"]
9644 pub target_data: CameraTrackingTargetData,
9645 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
9646 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
9647 pub camera_device_id: u8,
9648}
9649impl CAMERA_TRACKING_IMAGE_STATUS_DATA {
9650 pub const ENCODED_LEN: usize = 32usize;
9651 pub const DEFAULT: Self = Self {
9652 point_x: 0.0_f32,
9653 point_y: 0.0_f32,
9654 radius: 0.0_f32,
9655 rec_top_x: 0.0_f32,
9656 rec_top_y: 0.0_f32,
9657 rec_bottom_x: 0.0_f32,
9658 rec_bottom_y: 0.0_f32,
9659 tracking_status: CameraTrackingStatusFlags::DEFAULT,
9660 tracking_mode: CameraTrackingMode::DEFAULT,
9661 target_data: CameraTrackingTargetData::DEFAULT,
9662 camera_device_id: 0_u8,
9663 };
9664 #[cfg(feature = "arbitrary")]
9665 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9666 use arbitrary::{Arbitrary, Unstructured};
9667 let mut buf = [0u8; 1024];
9668 rng.fill_bytes(&mut buf);
9669 let mut unstructured = Unstructured::new(&buf);
9670 Self::arbitrary(&mut unstructured).unwrap_or_default()
9671 }
9672}
9673impl Default for CAMERA_TRACKING_IMAGE_STATUS_DATA {
9674 fn default() -> Self {
9675 Self::DEFAULT.clone()
9676 }
9677}
9678impl MessageData for CAMERA_TRACKING_IMAGE_STATUS_DATA {
9679 type Message = MavMessage;
9680 const ID: u32 = 275u32;
9681 const NAME: &'static str = "CAMERA_TRACKING_IMAGE_STATUS";
9682 const EXTRA_CRC: u8 = 126u8;
9683 const ENCODED_LEN: usize = 32usize;
9684 fn deser(
9685 _version: MavlinkVersion,
9686 __input: &[u8],
9687 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9688 let avail_len = __input.len();
9689 let mut payload_buf = [0; Self::ENCODED_LEN];
9690 let mut buf = if avail_len < Self::ENCODED_LEN {
9691 payload_buf[0..avail_len].copy_from_slice(__input);
9692 Bytes::new(&payload_buf)
9693 } else {
9694 Bytes::new(__input)
9695 };
9696 let mut __struct = Self::default();
9697 __struct.point_x = buf.get_f32_le()?;
9698 __struct.point_y = buf.get_f32_le()?;
9699 __struct.radius = buf.get_f32_le()?;
9700 __struct.rec_top_x = buf.get_f32_le()?;
9701 __struct.rec_top_y = buf.get_f32_le()?;
9702 __struct.rec_bottom_x = buf.get_f32_le()?;
9703 __struct.rec_bottom_y = buf.get_f32_le()?;
9704 let tmp = buf.get_u8()?;
9705 __struct.tracking_status =
9706 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9707 enum_type: "CameraTrackingStatusFlags",
9708 value: tmp as u64,
9709 })?;
9710 let tmp = buf.get_u8()?;
9711 __struct.tracking_mode =
9712 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9713 enum_type: "CameraTrackingMode",
9714 value: tmp as u64,
9715 })?;
9716 let tmp = buf.get_u8()?;
9717 __struct.target_data =
9718 CameraTrackingTargetData::from_bits(tmp as <CameraTrackingTargetData as Flags>::Bits)
9719 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
9720 flag_type: "CameraTrackingTargetData",
9721 value: tmp as u64,
9722 })?;
9723 __struct.camera_device_id = buf.get_u8()?;
9724 Ok(__struct)
9725 }
9726 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9727 let mut __tmp = BytesMut::new(bytes);
9728 #[allow(clippy::absurd_extreme_comparisons)]
9729 #[allow(unused_comparisons)]
9730 if __tmp.remaining() < Self::ENCODED_LEN {
9731 panic!(
9732 "buffer is too small (need {} bytes, but got {})",
9733 Self::ENCODED_LEN,
9734 __tmp.remaining(),
9735 )
9736 }
9737 __tmp.put_f32_le(self.point_x);
9738 __tmp.put_f32_le(self.point_y);
9739 __tmp.put_f32_le(self.radius);
9740 __tmp.put_f32_le(self.rec_top_x);
9741 __tmp.put_f32_le(self.rec_top_y);
9742 __tmp.put_f32_le(self.rec_bottom_x);
9743 __tmp.put_f32_le(self.rec_bottom_y);
9744 __tmp.put_u8(self.tracking_status as u8);
9745 __tmp.put_u8(self.tracking_mode as u8);
9746 __tmp.put_u8(self.target_data.bits() as u8);
9747 if matches!(version, MavlinkVersion::V2) {
9748 __tmp.put_u8(self.camera_device_id);
9749 let len = __tmp.len();
9750 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9751 } else {
9752 __tmp.len()
9753 }
9754 }
9755}
9756#[doc = "Camera-IMU triggering and synchronisation message."]
9757#[doc = ""]
9758#[doc = "ID: 112"]
9759#[derive(Debug, Clone, PartialEq)]
9760#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9761#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9762#[cfg_attr(feature = "ts", derive(TS))]
9763#[cfg_attr(feature = "ts", ts(export))]
9764pub struct CAMERA_TRIGGER_DATA {
9765 #[doc = "Timestamp for image frame (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
9766 pub time_usec: u64,
9767 #[doc = "Image frame sequence"]
9768 pub seq: u32,
9769}
9770impl CAMERA_TRIGGER_DATA {
9771 pub const ENCODED_LEN: usize = 12usize;
9772 pub const DEFAULT: Self = Self {
9773 time_usec: 0_u64,
9774 seq: 0_u32,
9775 };
9776 #[cfg(feature = "arbitrary")]
9777 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9778 use arbitrary::{Arbitrary, Unstructured};
9779 let mut buf = [0u8; 1024];
9780 rng.fill_bytes(&mut buf);
9781 let mut unstructured = Unstructured::new(&buf);
9782 Self::arbitrary(&mut unstructured).unwrap_or_default()
9783 }
9784}
9785impl Default for CAMERA_TRIGGER_DATA {
9786 fn default() -> Self {
9787 Self::DEFAULT.clone()
9788 }
9789}
9790impl MessageData for CAMERA_TRIGGER_DATA {
9791 type Message = MavMessage;
9792 const ID: u32 = 112u32;
9793 const NAME: &'static str = "CAMERA_TRIGGER";
9794 const EXTRA_CRC: u8 = 174u8;
9795 const ENCODED_LEN: usize = 12usize;
9796 fn deser(
9797 _version: MavlinkVersion,
9798 __input: &[u8],
9799 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9800 let avail_len = __input.len();
9801 let mut payload_buf = [0; Self::ENCODED_LEN];
9802 let mut buf = if avail_len < Self::ENCODED_LEN {
9803 payload_buf[0..avail_len].copy_from_slice(__input);
9804 Bytes::new(&payload_buf)
9805 } else {
9806 Bytes::new(__input)
9807 };
9808 let mut __struct = Self::default();
9809 __struct.time_usec = buf.get_u64_le()?;
9810 __struct.seq = buf.get_u32_le()?;
9811 Ok(__struct)
9812 }
9813 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9814 let mut __tmp = BytesMut::new(bytes);
9815 #[allow(clippy::absurd_extreme_comparisons)]
9816 #[allow(unused_comparisons)]
9817 if __tmp.remaining() < Self::ENCODED_LEN {
9818 panic!(
9819 "buffer is too small (need {} bytes, but got {})",
9820 Self::ENCODED_LEN,
9821 __tmp.remaining(),
9822 )
9823 }
9824 __tmp.put_u64_le(self.time_usec);
9825 __tmp.put_u32_le(self.seq);
9826 if matches!(version, MavlinkVersion::V2) {
9827 let len = __tmp.len();
9828 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9829 } else {
9830 __tmp.len()
9831 }
9832 }
9833}
9834#[doc = "A forwarded CANFD frame as requested by MAV_CMD_CAN_FORWARD. These are separated from CAN_FRAME as they need different handling (eg. TAO handling)."]
9835#[doc = ""]
9836#[doc = "ID: 387"]
9837#[derive(Debug, Clone, PartialEq)]
9838#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9839#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9840#[cfg_attr(feature = "ts", derive(TS))]
9841#[cfg_attr(feature = "ts", ts(export))]
9842pub struct CANFD_FRAME_DATA {
9843 #[doc = "Frame ID"]
9844 pub id: u32,
9845 #[doc = "System ID."]
9846 pub target_system: u8,
9847 #[doc = "Component ID."]
9848 pub target_component: u8,
9849 #[doc = "bus number"]
9850 pub bus: u8,
9851 #[doc = "Frame length"]
9852 pub len: u8,
9853 #[doc = "Frame data"]
9854 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9855 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
9856 pub data: [u8; 64],
9857}
9858impl CANFD_FRAME_DATA {
9859 pub const ENCODED_LEN: usize = 72usize;
9860 pub const DEFAULT: Self = Self {
9861 id: 0_u32,
9862 target_system: 0_u8,
9863 target_component: 0_u8,
9864 bus: 0_u8,
9865 len: 0_u8,
9866 data: [0_u8; 64usize],
9867 };
9868 #[cfg(feature = "arbitrary")]
9869 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9870 use arbitrary::{Arbitrary, Unstructured};
9871 let mut buf = [0u8; 1024];
9872 rng.fill_bytes(&mut buf);
9873 let mut unstructured = Unstructured::new(&buf);
9874 Self::arbitrary(&mut unstructured).unwrap_or_default()
9875 }
9876}
9877impl Default for CANFD_FRAME_DATA {
9878 fn default() -> Self {
9879 Self::DEFAULT.clone()
9880 }
9881}
9882impl MessageData for CANFD_FRAME_DATA {
9883 type Message = MavMessage;
9884 const ID: u32 = 387u32;
9885 const NAME: &'static str = "CANFD_FRAME";
9886 const EXTRA_CRC: u8 = 4u8;
9887 const ENCODED_LEN: usize = 72usize;
9888 fn deser(
9889 _version: MavlinkVersion,
9890 __input: &[u8],
9891 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9892 let avail_len = __input.len();
9893 let mut payload_buf = [0; Self::ENCODED_LEN];
9894 let mut buf = if avail_len < Self::ENCODED_LEN {
9895 payload_buf[0..avail_len].copy_from_slice(__input);
9896 Bytes::new(&payload_buf)
9897 } else {
9898 Bytes::new(__input)
9899 };
9900 let mut __struct = Self::default();
9901 __struct.id = buf.get_u32_le()?;
9902 __struct.target_system = buf.get_u8()?;
9903 __struct.target_component = buf.get_u8()?;
9904 __struct.bus = buf.get_u8()?;
9905 __struct.len = buf.get_u8()?;
9906 for v in &mut __struct.data {
9907 let val = buf.get_u8()?;
9908 *v = val;
9909 }
9910 Ok(__struct)
9911 }
9912 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9913 let mut __tmp = BytesMut::new(bytes);
9914 #[allow(clippy::absurd_extreme_comparisons)]
9915 #[allow(unused_comparisons)]
9916 if __tmp.remaining() < Self::ENCODED_LEN {
9917 panic!(
9918 "buffer is too small (need {} bytes, but got {})",
9919 Self::ENCODED_LEN,
9920 __tmp.remaining(),
9921 )
9922 }
9923 __tmp.put_u32_le(self.id);
9924 __tmp.put_u8(self.target_system);
9925 __tmp.put_u8(self.target_component);
9926 __tmp.put_u8(self.bus);
9927 __tmp.put_u8(self.len);
9928 for val in &self.data {
9929 __tmp.put_u8(*val);
9930 }
9931 if matches!(version, MavlinkVersion::V2) {
9932 let len = __tmp.len();
9933 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9934 } else {
9935 __tmp.len()
9936 }
9937 }
9938}
9939#[doc = "Modify the filter of what CAN messages to forward over the mavlink. This can be used to make CAN forwarding work well on low bandwidth links. The filtering is applied on bits 8 to 24 of the CAN id (2nd and 3rd bytes) which corresponds to the DroneCAN message ID for DroneCAN. Filters with more than 16 IDs can be constructed by sending multiple CAN_FILTER_MODIFY messages."]
9940#[doc = ""]
9941#[doc = "ID: 388"]
9942#[derive(Debug, Clone, PartialEq)]
9943#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9944#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9945#[cfg_attr(feature = "ts", derive(TS))]
9946#[cfg_attr(feature = "ts", ts(export))]
9947pub struct CAN_FILTER_MODIFY_DATA {
9948 #[doc = "filter IDs, length num_ids"]
9949 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9950 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
9951 pub ids: [u16; 16],
9952 #[doc = "System ID."]
9953 pub target_system: u8,
9954 #[doc = "Component ID."]
9955 pub target_component: u8,
9956 #[doc = "bus number"]
9957 pub bus: u8,
9958 #[doc = "what operation to perform on the filter list. See CAN_FILTER_OP enum."]
9959 pub operation: CanFilterOp,
9960 #[doc = "number of IDs in filter list"]
9961 pub num_ids: u8,
9962}
9963impl CAN_FILTER_MODIFY_DATA {
9964 pub const ENCODED_LEN: usize = 37usize;
9965 pub const DEFAULT: Self = Self {
9966 ids: [0_u16; 16usize],
9967 target_system: 0_u8,
9968 target_component: 0_u8,
9969 bus: 0_u8,
9970 operation: CanFilterOp::DEFAULT,
9971 num_ids: 0_u8,
9972 };
9973 #[cfg(feature = "arbitrary")]
9974 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9975 use arbitrary::{Arbitrary, Unstructured};
9976 let mut buf = [0u8; 1024];
9977 rng.fill_bytes(&mut buf);
9978 let mut unstructured = Unstructured::new(&buf);
9979 Self::arbitrary(&mut unstructured).unwrap_or_default()
9980 }
9981}
9982impl Default for CAN_FILTER_MODIFY_DATA {
9983 fn default() -> Self {
9984 Self::DEFAULT.clone()
9985 }
9986}
9987impl MessageData for CAN_FILTER_MODIFY_DATA {
9988 type Message = MavMessage;
9989 const ID: u32 = 388u32;
9990 const NAME: &'static str = "CAN_FILTER_MODIFY";
9991 const EXTRA_CRC: u8 = 8u8;
9992 const ENCODED_LEN: usize = 37usize;
9993 fn deser(
9994 _version: MavlinkVersion,
9995 __input: &[u8],
9996 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9997 let avail_len = __input.len();
9998 let mut payload_buf = [0; Self::ENCODED_LEN];
9999 let mut buf = if avail_len < Self::ENCODED_LEN {
10000 payload_buf[0..avail_len].copy_from_slice(__input);
10001 Bytes::new(&payload_buf)
10002 } else {
10003 Bytes::new(__input)
10004 };
10005 let mut __struct = Self::default();
10006 for v in &mut __struct.ids {
10007 let val = buf.get_u16_le()?;
10008 *v = val;
10009 }
10010 __struct.target_system = buf.get_u8()?;
10011 __struct.target_component = buf.get_u8()?;
10012 __struct.bus = buf.get_u8()?;
10013 let tmp = buf.get_u8()?;
10014 __struct.operation =
10015 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10016 enum_type: "CanFilterOp",
10017 value: tmp as u64,
10018 })?;
10019 __struct.num_ids = buf.get_u8()?;
10020 Ok(__struct)
10021 }
10022 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10023 let mut __tmp = BytesMut::new(bytes);
10024 #[allow(clippy::absurd_extreme_comparisons)]
10025 #[allow(unused_comparisons)]
10026 if __tmp.remaining() < Self::ENCODED_LEN {
10027 panic!(
10028 "buffer is too small (need {} bytes, but got {})",
10029 Self::ENCODED_LEN,
10030 __tmp.remaining(),
10031 )
10032 }
10033 for val in &self.ids {
10034 __tmp.put_u16_le(*val);
10035 }
10036 __tmp.put_u8(self.target_system);
10037 __tmp.put_u8(self.target_component);
10038 __tmp.put_u8(self.bus);
10039 __tmp.put_u8(self.operation as u8);
10040 __tmp.put_u8(self.num_ids);
10041 if matches!(version, MavlinkVersion::V2) {
10042 let len = __tmp.len();
10043 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10044 } else {
10045 __tmp.len()
10046 }
10047 }
10048}
10049#[doc = "A forwarded CAN frame as requested by MAV_CMD_CAN_FORWARD."]
10050#[doc = ""]
10051#[doc = "ID: 386"]
10052#[derive(Debug, Clone, PartialEq)]
10053#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10054#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10055#[cfg_attr(feature = "ts", derive(TS))]
10056#[cfg_attr(feature = "ts", ts(export))]
10057pub struct CAN_FRAME_DATA {
10058 #[doc = "Frame ID"]
10059 pub id: u32,
10060 #[doc = "System ID."]
10061 pub target_system: u8,
10062 #[doc = "Component ID."]
10063 pub target_component: u8,
10064 #[doc = "Bus number"]
10065 pub bus: u8,
10066 #[doc = "Frame length"]
10067 pub len: u8,
10068 #[doc = "Frame data"]
10069 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10070 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
10071 pub data: [u8; 8],
10072}
10073impl CAN_FRAME_DATA {
10074 pub const ENCODED_LEN: usize = 16usize;
10075 pub const DEFAULT: Self = Self {
10076 id: 0_u32,
10077 target_system: 0_u8,
10078 target_component: 0_u8,
10079 bus: 0_u8,
10080 len: 0_u8,
10081 data: [0_u8; 8usize],
10082 };
10083 #[cfg(feature = "arbitrary")]
10084 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10085 use arbitrary::{Arbitrary, Unstructured};
10086 let mut buf = [0u8; 1024];
10087 rng.fill_bytes(&mut buf);
10088 let mut unstructured = Unstructured::new(&buf);
10089 Self::arbitrary(&mut unstructured).unwrap_or_default()
10090 }
10091}
10092impl Default for CAN_FRAME_DATA {
10093 fn default() -> Self {
10094 Self::DEFAULT.clone()
10095 }
10096}
10097impl MessageData for CAN_FRAME_DATA {
10098 type Message = MavMessage;
10099 const ID: u32 = 386u32;
10100 const NAME: &'static str = "CAN_FRAME";
10101 const EXTRA_CRC: u8 = 132u8;
10102 const ENCODED_LEN: usize = 16usize;
10103 fn deser(
10104 _version: MavlinkVersion,
10105 __input: &[u8],
10106 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10107 let avail_len = __input.len();
10108 let mut payload_buf = [0; Self::ENCODED_LEN];
10109 let mut buf = if avail_len < Self::ENCODED_LEN {
10110 payload_buf[0..avail_len].copy_from_slice(__input);
10111 Bytes::new(&payload_buf)
10112 } else {
10113 Bytes::new(__input)
10114 };
10115 let mut __struct = Self::default();
10116 __struct.id = buf.get_u32_le()?;
10117 __struct.target_system = buf.get_u8()?;
10118 __struct.target_component = buf.get_u8()?;
10119 __struct.bus = buf.get_u8()?;
10120 __struct.len = buf.get_u8()?;
10121 for v in &mut __struct.data {
10122 let val = buf.get_u8()?;
10123 *v = val;
10124 }
10125 Ok(__struct)
10126 }
10127 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10128 let mut __tmp = BytesMut::new(bytes);
10129 #[allow(clippy::absurd_extreme_comparisons)]
10130 #[allow(unused_comparisons)]
10131 if __tmp.remaining() < Self::ENCODED_LEN {
10132 panic!(
10133 "buffer is too small (need {} bytes, but got {})",
10134 Self::ENCODED_LEN,
10135 __tmp.remaining(),
10136 )
10137 }
10138 __tmp.put_u32_le(self.id);
10139 __tmp.put_u8(self.target_system);
10140 __tmp.put_u8(self.target_component);
10141 __tmp.put_u8(self.bus);
10142 __tmp.put_u8(self.len);
10143 for val in &self.data {
10144 __tmp.put_u8(*val);
10145 }
10146 if matches!(version, MavlinkVersion::V2) {
10147 let len = __tmp.len();
10148 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10149 } else {
10150 __tmp.len()
10151 }
10152 }
10153}
10154#[doc = "Configure cellular modems. This message is re-emitted as an acknowledgement by the modem. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE."]
10155#[doc = ""]
10156#[doc = "ID: 336"]
10157#[derive(Debug, Clone, PartialEq)]
10158#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10159#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10160#[cfg_attr(feature = "ts", derive(TS))]
10161#[cfg_attr(feature = "ts", ts(export))]
10162pub struct CELLULAR_CONFIG_DATA {
10163 #[doc = "Enable/disable LTE. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response."]
10164 pub enable_lte: u8,
10165 #[doc = "Enable/disable PIN on the SIM card. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response."]
10166 pub enable_pin: u8,
10167 #[doc = "PIN sent to the SIM card. Blank when PIN is disabled. Empty when message is sent back as a response."]
10168 #[cfg_attr(feature = "ts", ts(type = "string"))]
10169 pub pin: CharArray<16>,
10170 #[doc = "New PIN when changing the PIN. Blank to leave it unchanged. Empty when message is sent back as a response."]
10171 #[cfg_attr(feature = "ts", ts(type = "string"))]
10172 pub new_pin: CharArray<16>,
10173 #[doc = "Name of the cellular APN. Blank to leave it unchanged. Current APN when sent back as a response."]
10174 #[cfg_attr(feature = "ts", ts(type = "string"))]
10175 pub apn: CharArray<32>,
10176 #[doc = "Required PUK code in case the user failed to authenticate 3 times with the PIN. Empty when message is sent back as a response."]
10177 #[cfg_attr(feature = "ts", ts(type = "string"))]
10178 pub puk: CharArray<16>,
10179 #[doc = "Enable/disable roaming. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response."]
10180 pub roaming: u8,
10181 #[doc = "Message acceptance response (sent back to GS)."]
10182 pub response: CellularConfigResponse,
10183}
10184impl CELLULAR_CONFIG_DATA {
10185 pub const ENCODED_LEN: usize = 84usize;
10186 pub const DEFAULT: Self = Self {
10187 enable_lte: 0_u8,
10188 enable_pin: 0_u8,
10189 pin: CharArray::new([0_u8; 16usize]),
10190 new_pin: CharArray::new([0_u8; 16usize]),
10191 apn: CharArray::new([0_u8; 32usize]),
10192 puk: CharArray::new([0_u8; 16usize]),
10193 roaming: 0_u8,
10194 response: CellularConfigResponse::DEFAULT,
10195 };
10196 #[cfg(feature = "arbitrary")]
10197 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10198 use arbitrary::{Arbitrary, Unstructured};
10199 let mut buf = [0u8; 1024];
10200 rng.fill_bytes(&mut buf);
10201 let mut unstructured = Unstructured::new(&buf);
10202 Self::arbitrary(&mut unstructured).unwrap_or_default()
10203 }
10204}
10205impl Default for CELLULAR_CONFIG_DATA {
10206 fn default() -> Self {
10207 Self::DEFAULT.clone()
10208 }
10209}
10210impl MessageData for CELLULAR_CONFIG_DATA {
10211 type Message = MavMessage;
10212 const ID: u32 = 336u32;
10213 const NAME: &'static str = "CELLULAR_CONFIG";
10214 const EXTRA_CRC: u8 = 245u8;
10215 const ENCODED_LEN: usize = 84usize;
10216 fn deser(
10217 _version: MavlinkVersion,
10218 __input: &[u8],
10219 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10220 let avail_len = __input.len();
10221 let mut payload_buf = [0; Self::ENCODED_LEN];
10222 let mut buf = if avail_len < Self::ENCODED_LEN {
10223 payload_buf[0..avail_len].copy_from_slice(__input);
10224 Bytes::new(&payload_buf)
10225 } else {
10226 Bytes::new(__input)
10227 };
10228 let mut __struct = Self::default();
10229 __struct.enable_lte = buf.get_u8()?;
10230 __struct.enable_pin = buf.get_u8()?;
10231 let mut tmp = [0_u8; 16usize];
10232 for v in &mut tmp {
10233 *v = buf.get_u8()?;
10234 }
10235 __struct.pin = CharArray::new(tmp);
10236 let mut tmp = [0_u8; 16usize];
10237 for v in &mut tmp {
10238 *v = buf.get_u8()?;
10239 }
10240 __struct.new_pin = CharArray::new(tmp);
10241 let mut tmp = [0_u8; 32usize];
10242 for v in &mut tmp {
10243 *v = buf.get_u8()?;
10244 }
10245 __struct.apn = CharArray::new(tmp);
10246 let mut tmp = [0_u8; 16usize];
10247 for v in &mut tmp {
10248 *v = buf.get_u8()?;
10249 }
10250 __struct.puk = CharArray::new(tmp);
10251 __struct.roaming = buf.get_u8()?;
10252 let tmp = buf.get_u8()?;
10253 __struct.response =
10254 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10255 enum_type: "CellularConfigResponse",
10256 value: tmp as u64,
10257 })?;
10258 Ok(__struct)
10259 }
10260 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10261 let mut __tmp = BytesMut::new(bytes);
10262 #[allow(clippy::absurd_extreme_comparisons)]
10263 #[allow(unused_comparisons)]
10264 if __tmp.remaining() < Self::ENCODED_LEN {
10265 panic!(
10266 "buffer is too small (need {} bytes, but got {})",
10267 Self::ENCODED_LEN,
10268 __tmp.remaining(),
10269 )
10270 }
10271 __tmp.put_u8(self.enable_lte);
10272 __tmp.put_u8(self.enable_pin);
10273 for val in &self.pin {
10274 __tmp.put_u8(*val);
10275 }
10276 for val in &self.new_pin {
10277 __tmp.put_u8(*val);
10278 }
10279 for val in &self.apn {
10280 __tmp.put_u8(*val);
10281 }
10282 for val in &self.puk {
10283 __tmp.put_u8(*val);
10284 }
10285 __tmp.put_u8(self.roaming);
10286 __tmp.put_u8(self.response as u8);
10287 if matches!(version, MavlinkVersion::V2) {
10288 let len = __tmp.len();
10289 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10290 } else {
10291 __tmp.len()
10292 }
10293 }
10294}
10295#[doc = "Report current used cellular network status."]
10296#[doc = ""]
10297#[doc = "ID: 334"]
10298#[derive(Debug, Clone, PartialEq)]
10299#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10300#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10301#[cfg_attr(feature = "ts", derive(TS))]
10302#[cfg_attr(feature = "ts", ts(export))]
10303pub struct CELLULAR_STATUS_DATA {
10304 #[doc = "Mobile country code. If unknown, set to UINT16_MAX"]
10305 pub mcc: u16,
10306 #[doc = "Mobile network code. If unknown, set to UINT16_MAX"]
10307 pub mnc: u16,
10308 #[doc = "Location area code. If unknown, set to 0"]
10309 pub lac: u16,
10310 #[doc = "Cellular modem status"]
10311 pub status: CellularStatusFlag,
10312 #[doc = "Failure reason when status in in CELLULAR_STATUS_FLAG_FAILED"]
10313 pub failure_reason: CellularNetworkFailedReason,
10314 #[doc = "Cellular network radio type: gsm, cdma, lte..."]
10315 pub mavtype: CellularNetworkRadioType,
10316 #[doc = "Signal quality in percent. If unknown, set to UINT8_MAX"]
10317 pub quality: u8,
10318}
10319impl CELLULAR_STATUS_DATA {
10320 pub const ENCODED_LEN: usize = 10usize;
10321 pub const DEFAULT: Self = Self {
10322 mcc: 0_u16,
10323 mnc: 0_u16,
10324 lac: 0_u16,
10325 status: CellularStatusFlag::DEFAULT,
10326 failure_reason: CellularNetworkFailedReason::DEFAULT,
10327 mavtype: CellularNetworkRadioType::DEFAULT,
10328 quality: 0_u8,
10329 };
10330 #[cfg(feature = "arbitrary")]
10331 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10332 use arbitrary::{Arbitrary, Unstructured};
10333 let mut buf = [0u8; 1024];
10334 rng.fill_bytes(&mut buf);
10335 let mut unstructured = Unstructured::new(&buf);
10336 Self::arbitrary(&mut unstructured).unwrap_or_default()
10337 }
10338}
10339impl Default for CELLULAR_STATUS_DATA {
10340 fn default() -> Self {
10341 Self::DEFAULT.clone()
10342 }
10343}
10344impl MessageData for CELLULAR_STATUS_DATA {
10345 type Message = MavMessage;
10346 const ID: u32 = 334u32;
10347 const NAME: &'static str = "CELLULAR_STATUS";
10348 const EXTRA_CRC: u8 = 72u8;
10349 const ENCODED_LEN: usize = 10usize;
10350 fn deser(
10351 _version: MavlinkVersion,
10352 __input: &[u8],
10353 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10354 let avail_len = __input.len();
10355 let mut payload_buf = [0; Self::ENCODED_LEN];
10356 let mut buf = if avail_len < Self::ENCODED_LEN {
10357 payload_buf[0..avail_len].copy_from_slice(__input);
10358 Bytes::new(&payload_buf)
10359 } else {
10360 Bytes::new(__input)
10361 };
10362 let mut __struct = Self::default();
10363 __struct.mcc = buf.get_u16_le()?;
10364 __struct.mnc = buf.get_u16_le()?;
10365 __struct.lac = buf.get_u16_le()?;
10366 let tmp = buf.get_u8()?;
10367 __struct.status =
10368 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10369 enum_type: "CellularStatusFlag",
10370 value: tmp as u64,
10371 })?;
10372 let tmp = buf.get_u8()?;
10373 __struct.failure_reason =
10374 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10375 enum_type: "CellularNetworkFailedReason",
10376 value: tmp as u64,
10377 })?;
10378 let tmp = buf.get_u8()?;
10379 __struct.mavtype =
10380 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10381 enum_type: "CellularNetworkRadioType",
10382 value: tmp as u64,
10383 })?;
10384 __struct.quality = buf.get_u8()?;
10385 Ok(__struct)
10386 }
10387 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10388 let mut __tmp = BytesMut::new(bytes);
10389 #[allow(clippy::absurd_extreme_comparisons)]
10390 #[allow(unused_comparisons)]
10391 if __tmp.remaining() < Self::ENCODED_LEN {
10392 panic!(
10393 "buffer is too small (need {} bytes, but got {})",
10394 Self::ENCODED_LEN,
10395 __tmp.remaining(),
10396 )
10397 }
10398 __tmp.put_u16_le(self.mcc);
10399 __tmp.put_u16_le(self.mnc);
10400 __tmp.put_u16_le(self.lac);
10401 __tmp.put_u8(self.status as u8);
10402 __tmp.put_u8(self.failure_reason as u8);
10403 __tmp.put_u8(self.mavtype as u8);
10404 __tmp.put_u8(self.quality);
10405 if matches!(version, MavlinkVersion::V2) {
10406 let len = __tmp.len();
10407 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10408 } else {
10409 __tmp.len()
10410 }
10411 }
10412}
10413#[doc = "Request to control this MAV."]
10414#[doc = ""]
10415#[doc = "ID: 5"]
10416#[derive(Debug, Clone, PartialEq)]
10417#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10418#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10419#[cfg_attr(feature = "ts", derive(TS))]
10420#[cfg_attr(feature = "ts", ts(export))]
10421pub struct CHANGE_OPERATOR_CONTROL_DATA {
10422 #[doc = "System the GCS requests control for"]
10423 pub target_system: u8,
10424 #[doc = "0: request control of this MAV, 1: Release control of this MAV"]
10425 pub control_request: u8,
10426 #[doc = "0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch."]
10427 pub version: u8,
10428 #[doc = "Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and \"!?,.-\""]
10429 #[cfg_attr(feature = "ts", ts(type = "string"))]
10430 pub passkey: CharArray<25>,
10431}
10432impl CHANGE_OPERATOR_CONTROL_DATA {
10433 pub const ENCODED_LEN: usize = 28usize;
10434 pub const DEFAULT: Self = Self {
10435 target_system: 0_u8,
10436 control_request: 0_u8,
10437 version: 0_u8,
10438 passkey: CharArray::new([0_u8; 25usize]),
10439 };
10440 #[cfg(feature = "arbitrary")]
10441 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10442 use arbitrary::{Arbitrary, Unstructured};
10443 let mut buf = [0u8; 1024];
10444 rng.fill_bytes(&mut buf);
10445 let mut unstructured = Unstructured::new(&buf);
10446 Self::arbitrary(&mut unstructured).unwrap_or_default()
10447 }
10448}
10449impl Default for CHANGE_OPERATOR_CONTROL_DATA {
10450 fn default() -> Self {
10451 Self::DEFAULT.clone()
10452 }
10453}
10454impl MessageData for CHANGE_OPERATOR_CONTROL_DATA {
10455 type Message = MavMessage;
10456 const ID: u32 = 5u32;
10457 const NAME: &'static str = "CHANGE_OPERATOR_CONTROL";
10458 const EXTRA_CRC: u8 = 217u8;
10459 const ENCODED_LEN: usize = 28usize;
10460 fn deser(
10461 _version: MavlinkVersion,
10462 __input: &[u8],
10463 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10464 let avail_len = __input.len();
10465 let mut payload_buf = [0; Self::ENCODED_LEN];
10466 let mut buf = if avail_len < Self::ENCODED_LEN {
10467 payload_buf[0..avail_len].copy_from_slice(__input);
10468 Bytes::new(&payload_buf)
10469 } else {
10470 Bytes::new(__input)
10471 };
10472 let mut __struct = Self::default();
10473 __struct.target_system = buf.get_u8()?;
10474 __struct.control_request = buf.get_u8()?;
10475 __struct.version = buf.get_u8()?;
10476 let mut tmp = [0_u8; 25usize];
10477 for v in &mut tmp {
10478 *v = buf.get_u8()?;
10479 }
10480 __struct.passkey = CharArray::new(tmp);
10481 Ok(__struct)
10482 }
10483 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10484 let mut __tmp = BytesMut::new(bytes);
10485 #[allow(clippy::absurd_extreme_comparisons)]
10486 #[allow(unused_comparisons)]
10487 if __tmp.remaining() < Self::ENCODED_LEN {
10488 panic!(
10489 "buffer is too small (need {} bytes, but got {})",
10490 Self::ENCODED_LEN,
10491 __tmp.remaining(),
10492 )
10493 }
10494 __tmp.put_u8(self.target_system);
10495 __tmp.put_u8(self.control_request);
10496 __tmp.put_u8(self.version);
10497 for val in &self.passkey {
10498 __tmp.put_u8(*val);
10499 }
10500 if matches!(version, MavlinkVersion::V2) {
10501 let len = __tmp.len();
10502 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10503 } else {
10504 __tmp.len()
10505 }
10506 }
10507}
10508#[doc = "Accept / deny control of this MAV."]
10509#[doc = ""]
10510#[doc = "ID: 6"]
10511#[derive(Debug, Clone, PartialEq)]
10512#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10513#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10514#[cfg_attr(feature = "ts", derive(TS))]
10515#[cfg_attr(feature = "ts", ts(export))]
10516pub struct CHANGE_OPERATOR_CONTROL_ACK_DATA {
10517 #[doc = "ID of the GCS this message"]
10518 pub gcs_system_id: u8,
10519 #[doc = "0: request control of this MAV, 1: Release control of this MAV"]
10520 pub control_request: u8,
10521 #[doc = "0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control"]
10522 pub ack: u8,
10523}
10524impl CHANGE_OPERATOR_CONTROL_ACK_DATA {
10525 pub const ENCODED_LEN: usize = 3usize;
10526 pub const DEFAULT: Self = Self {
10527 gcs_system_id: 0_u8,
10528 control_request: 0_u8,
10529 ack: 0_u8,
10530 };
10531 #[cfg(feature = "arbitrary")]
10532 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10533 use arbitrary::{Arbitrary, Unstructured};
10534 let mut buf = [0u8; 1024];
10535 rng.fill_bytes(&mut buf);
10536 let mut unstructured = Unstructured::new(&buf);
10537 Self::arbitrary(&mut unstructured).unwrap_or_default()
10538 }
10539}
10540impl Default for CHANGE_OPERATOR_CONTROL_ACK_DATA {
10541 fn default() -> Self {
10542 Self::DEFAULT.clone()
10543 }
10544}
10545impl MessageData for CHANGE_OPERATOR_CONTROL_ACK_DATA {
10546 type Message = MavMessage;
10547 const ID: u32 = 6u32;
10548 const NAME: &'static str = "CHANGE_OPERATOR_CONTROL_ACK";
10549 const EXTRA_CRC: u8 = 104u8;
10550 const ENCODED_LEN: usize = 3usize;
10551 fn deser(
10552 _version: MavlinkVersion,
10553 __input: &[u8],
10554 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10555 let avail_len = __input.len();
10556 let mut payload_buf = [0; Self::ENCODED_LEN];
10557 let mut buf = if avail_len < Self::ENCODED_LEN {
10558 payload_buf[0..avail_len].copy_from_slice(__input);
10559 Bytes::new(&payload_buf)
10560 } else {
10561 Bytes::new(__input)
10562 };
10563 let mut __struct = Self::default();
10564 __struct.gcs_system_id = buf.get_u8()?;
10565 __struct.control_request = buf.get_u8()?;
10566 __struct.ack = buf.get_u8()?;
10567 Ok(__struct)
10568 }
10569 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10570 let mut __tmp = BytesMut::new(bytes);
10571 #[allow(clippy::absurd_extreme_comparisons)]
10572 #[allow(unused_comparisons)]
10573 if __tmp.remaining() < Self::ENCODED_LEN {
10574 panic!(
10575 "buffer is too small (need {} bytes, but got {})",
10576 Self::ENCODED_LEN,
10577 __tmp.remaining(),
10578 )
10579 }
10580 __tmp.put_u8(self.gcs_system_id);
10581 __tmp.put_u8(self.control_request);
10582 __tmp.put_u8(self.ack);
10583 if matches!(version, MavlinkVersion::V2) {
10584 let len = __tmp.len();
10585 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10586 } else {
10587 __tmp.len()
10588 }
10589 }
10590}
10591#[doc = "Information about a potential collision."]
10592#[doc = ""]
10593#[doc = "ID: 247"]
10594#[derive(Debug, Clone, PartialEq)]
10595#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10596#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10597#[cfg_attr(feature = "ts", derive(TS))]
10598#[cfg_attr(feature = "ts", ts(export))]
10599pub struct COLLISION_DATA {
10600 #[doc = "Unique identifier, domain based on src field"]
10601 pub id: u32,
10602 #[doc = "Estimated time until collision occurs"]
10603 pub time_to_minimum_delta: f32,
10604 #[doc = "Closest vertical distance between vehicle and object"]
10605 pub altitude_minimum_delta: f32,
10606 #[doc = "Closest horizontal distance between vehicle and object"]
10607 pub horizontal_minimum_delta: f32,
10608 #[doc = "Collision data source"]
10609 pub src: MavCollisionSrc,
10610 #[doc = "Action that is being taken to avoid this collision"]
10611 pub action: MavCollisionAction,
10612 #[doc = "How concerned the aircraft is about this collision"]
10613 pub threat_level: MavCollisionThreatLevel,
10614}
10615impl COLLISION_DATA {
10616 pub const ENCODED_LEN: usize = 19usize;
10617 pub const DEFAULT: Self = Self {
10618 id: 0_u32,
10619 time_to_minimum_delta: 0.0_f32,
10620 altitude_minimum_delta: 0.0_f32,
10621 horizontal_minimum_delta: 0.0_f32,
10622 src: MavCollisionSrc::DEFAULT,
10623 action: MavCollisionAction::DEFAULT,
10624 threat_level: MavCollisionThreatLevel::DEFAULT,
10625 };
10626 #[cfg(feature = "arbitrary")]
10627 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10628 use arbitrary::{Arbitrary, Unstructured};
10629 let mut buf = [0u8; 1024];
10630 rng.fill_bytes(&mut buf);
10631 let mut unstructured = Unstructured::new(&buf);
10632 Self::arbitrary(&mut unstructured).unwrap_or_default()
10633 }
10634}
10635impl Default for COLLISION_DATA {
10636 fn default() -> Self {
10637 Self::DEFAULT.clone()
10638 }
10639}
10640impl MessageData for COLLISION_DATA {
10641 type Message = MavMessage;
10642 const ID: u32 = 247u32;
10643 const NAME: &'static str = "COLLISION";
10644 const EXTRA_CRC: u8 = 81u8;
10645 const ENCODED_LEN: usize = 19usize;
10646 fn deser(
10647 _version: MavlinkVersion,
10648 __input: &[u8],
10649 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10650 let avail_len = __input.len();
10651 let mut payload_buf = [0; Self::ENCODED_LEN];
10652 let mut buf = if avail_len < Self::ENCODED_LEN {
10653 payload_buf[0..avail_len].copy_from_slice(__input);
10654 Bytes::new(&payload_buf)
10655 } else {
10656 Bytes::new(__input)
10657 };
10658 let mut __struct = Self::default();
10659 __struct.id = buf.get_u32_le()?;
10660 __struct.time_to_minimum_delta = buf.get_f32_le()?;
10661 __struct.altitude_minimum_delta = buf.get_f32_le()?;
10662 __struct.horizontal_minimum_delta = buf.get_f32_le()?;
10663 let tmp = buf.get_u8()?;
10664 __struct.src =
10665 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10666 enum_type: "MavCollisionSrc",
10667 value: tmp as u64,
10668 })?;
10669 let tmp = buf.get_u8()?;
10670 __struct.action =
10671 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10672 enum_type: "MavCollisionAction",
10673 value: tmp as u64,
10674 })?;
10675 let tmp = buf.get_u8()?;
10676 __struct.threat_level =
10677 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10678 enum_type: "MavCollisionThreatLevel",
10679 value: tmp as u64,
10680 })?;
10681 Ok(__struct)
10682 }
10683 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10684 let mut __tmp = BytesMut::new(bytes);
10685 #[allow(clippy::absurd_extreme_comparisons)]
10686 #[allow(unused_comparisons)]
10687 if __tmp.remaining() < Self::ENCODED_LEN {
10688 panic!(
10689 "buffer is too small (need {} bytes, but got {})",
10690 Self::ENCODED_LEN,
10691 __tmp.remaining(),
10692 )
10693 }
10694 __tmp.put_u32_le(self.id);
10695 __tmp.put_f32_le(self.time_to_minimum_delta);
10696 __tmp.put_f32_le(self.altitude_minimum_delta);
10697 __tmp.put_f32_le(self.horizontal_minimum_delta);
10698 __tmp.put_u8(self.src as u8);
10699 __tmp.put_u8(self.action as u8);
10700 __tmp.put_u8(self.threat_level as u8);
10701 if matches!(version, MavlinkVersion::V2) {
10702 let len = __tmp.len();
10703 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10704 } else {
10705 __tmp.len()
10706 }
10707 }
10708}
10709#[doc = "Report status of a command. Includes feedback whether the command was executed. The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
10710#[doc = ""]
10711#[doc = "ID: 77"]
10712#[derive(Debug, Clone, PartialEq)]
10713#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10714#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10715#[cfg_attr(feature = "ts", derive(TS))]
10716#[cfg_attr(feature = "ts", ts(export))]
10717pub struct COMMAND_ACK_DATA {
10718 #[doc = "Command ID (of acknowledged command)."]
10719 pub command: MavCmd,
10720 #[doc = "Result of command."]
10721 pub result: MavResult,
10722 #[doc = "The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown."]
10723 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
10724 pub progress: u8,
10725 #[doc = "Additional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate \"unused\" or \"unknown\")."]
10726 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
10727 pub result_param2: i32,
10728 #[doc = "System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement."]
10729 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
10730 pub target_system: u8,
10731 #[doc = "Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement."]
10732 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
10733 pub target_component: u8,
10734}
10735impl COMMAND_ACK_DATA {
10736 pub const ENCODED_LEN: usize = 10usize;
10737 pub const DEFAULT: Self = Self {
10738 command: MavCmd::DEFAULT,
10739 result: MavResult::DEFAULT,
10740 progress: 0_u8,
10741 result_param2: 0_i32,
10742 target_system: 0_u8,
10743 target_component: 0_u8,
10744 };
10745 #[cfg(feature = "arbitrary")]
10746 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10747 use arbitrary::{Arbitrary, Unstructured};
10748 let mut buf = [0u8; 1024];
10749 rng.fill_bytes(&mut buf);
10750 let mut unstructured = Unstructured::new(&buf);
10751 Self::arbitrary(&mut unstructured).unwrap_or_default()
10752 }
10753}
10754impl Default for COMMAND_ACK_DATA {
10755 fn default() -> Self {
10756 Self::DEFAULT.clone()
10757 }
10758}
10759impl MessageData for COMMAND_ACK_DATA {
10760 type Message = MavMessage;
10761 const ID: u32 = 77u32;
10762 const NAME: &'static str = "COMMAND_ACK";
10763 const EXTRA_CRC: u8 = 143u8;
10764 const ENCODED_LEN: usize = 10usize;
10765 fn deser(
10766 _version: MavlinkVersion,
10767 __input: &[u8],
10768 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10769 let avail_len = __input.len();
10770 let mut payload_buf = [0; Self::ENCODED_LEN];
10771 let mut buf = if avail_len < Self::ENCODED_LEN {
10772 payload_buf[0..avail_len].copy_from_slice(__input);
10773 Bytes::new(&payload_buf)
10774 } else {
10775 Bytes::new(__input)
10776 };
10777 let mut __struct = Self::default();
10778 let tmp = buf.get_u16_le()?;
10779 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
10780 ::mavlink_core::error::ParserError::InvalidEnum {
10781 enum_type: "MavCmd",
10782 value: tmp as u64,
10783 },
10784 )?;
10785 let tmp = buf.get_u8()?;
10786 __struct.result =
10787 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10788 enum_type: "MavResult",
10789 value: tmp as u64,
10790 })?;
10791 __struct.progress = buf.get_u8()?;
10792 __struct.result_param2 = buf.get_i32_le()?;
10793 __struct.target_system = buf.get_u8()?;
10794 __struct.target_component = buf.get_u8()?;
10795 Ok(__struct)
10796 }
10797 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10798 let mut __tmp = BytesMut::new(bytes);
10799 #[allow(clippy::absurd_extreme_comparisons)]
10800 #[allow(unused_comparisons)]
10801 if __tmp.remaining() < Self::ENCODED_LEN {
10802 panic!(
10803 "buffer is too small (need {} bytes, but got {})",
10804 Self::ENCODED_LEN,
10805 __tmp.remaining(),
10806 )
10807 }
10808 __tmp.put_u16_le(self.command as u16);
10809 __tmp.put_u8(self.result as u8);
10810 if matches!(version, MavlinkVersion::V2) {
10811 __tmp.put_u8(self.progress);
10812 __tmp.put_i32_le(self.result_param2);
10813 __tmp.put_u8(self.target_system);
10814 __tmp.put_u8(self.target_component);
10815 let len = __tmp.len();
10816 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10817 } else {
10818 __tmp.len()
10819 }
10820 }
10821}
10822#[doc = "Cancel a long running command. The target system should respond with a COMMAND_ACK to the original command with result=MAV_RESULT_CANCELLED if the long running process was cancelled. If it has already completed, the cancel action can be ignored. The cancel action can be retried until some sort of acknowledgement to the original command has been received. The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
10823#[doc = ""]
10824#[doc = "ID: 80"]
10825#[derive(Debug, Clone, PartialEq)]
10826#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10827#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10828#[cfg_attr(feature = "ts", derive(TS))]
10829#[cfg_attr(feature = "ts", ts(export))]
10830pub struct COMMAND_CANCEL_DATA {
10831 #[doc = "Command ID (of command to cancel)."]
10832 pub command: MavCmd,
10833 #[doc = "System executing long running command. Should not be broadcast (0)."]
10834 pub target_system: u8,
10835 #[doc = "Component executing long running command."]
10836 pub target_component: u8,
10837}
10838impl COMMAND_CANCEL_DATA {
10839 pub const ENCODED_LEN: usize = 4usize;
10840 pub const DEFAULT: Self = Self {
10841 command: MavCmd::DEFAULT,
10842 target_system: 0_u8,
10843 target_component: 0_u8,
10844 };
10845 #[cfg(feature = "arbitrary")]
10846 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10847 use arbitrary::{Arbitrary, Unstructured};
10848 let mut buf = [0u8; 1024];
10849 rng.fill_bytes(&mut buf);
10850 let mut unstructured = Unstructured::new(&buf);
10851 Self::arbitrary(&mut unstructured).unwrap_or_default()
10852 }
10853}
10854impl Default for COMMAND_CANCEL_DATA {
10855 fn default() -> Self {
10856 Self::DEFAULT.clone()
10857 }
10858}
10859impl MessageData for COMMAND_CANCEL_DATA {
10860 type Message = MavMessage;
10861 const ID: u32 = 80u32;
10862 const NAME: &'static str = "COMMAND_CANCEL";
10863 const EXTRA_CRC: u8 = 14u8;
10864 const ENCODED_LEN: usize = 4usize;
10865 fn deser(
10866 _version: MavlinkVersion,
10867 __input: &[u8],
10868 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10869 let avail_len = __input.len();
10870 let mut payload_buf = [0; Self::ENCODED_LEN];
10871 let mut buf = if avail_len < Self::ENCODED_LEN {
10872 payload_buf[0..avail_len].copy_from_slice(__input);
10873 Bytes::new(&payload_buf)
10874 } else {
10875 Bytes::new(__input)
10876 };
10877 let mut __struct = Self::default();
10878 let tmp = buf.get_u16_le()?;
10879 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
10880 ::mavlink_core::error::ParserError::InvalidEnum {
10881 enum_type: "MavCmd",
10882 value: tmp as u64,
10883 },
10884 )?;
10885 __struct.target_system = buf.get_u8()?;
10886 __struct.target_component = buf.get_u8()?;
10887 Ok(__struct)
10888 }
10889 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10890 let mut __tmp = BytesMut::new(bytes);
10891 #[allow(clippy::absurd_extreme_comparisons)]
10892 #[allow(unused_comparisons)]
10893 if __tmp.remaining() < Self::ENCODED_LEN {
10894 panic!(
10895 "buffer is too small (need {} bytes, but got {})",
10896 Self::ENCODED_LEN,
10897 __tmp.remaining(),
10898 )
10899 }
10900 __tmp.put_u16_le(self.command as u16);
10901 __tmp.put_u8(self.target_system);
10902 __tmp.put_u8(self.target_component);
10903 if matches!(version, MavlinkVersion::V2) {
10904 let len = __tmp.len();
10905 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10906 } else {
10907 __tmp.len()
10908 }
10909 }
10910}
10911#[doc = "Send a command with up to seven parameters to the MAV, where params 5 and 6 are integers and the other values are floats. This is preferred over COMMAND_LONG as it allows the MAV_FRAME to be specified for interpreting positional information, such as altitude. COMMAND_INT is also preferred when sending latitude and longitude data in params 5 and 6, as it allows for greater precision. Param 5 and 6 encode positional data as scaled integers, where the scaling depends on the actual command value. NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
10912#[doc = ""]
10913#[doc = "ID: 75"]
10914#[derive(Debug, Clone, PartialEq)]
10915#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10916#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10917#[cfg_attr(feature = "ts", derive(TS))]
10918#[cfg_attr(feature = "ts", ts(export))]
10919pub struct COMMAND_INT_DATA {
10920 #[doc = "PARAM1, see MAV_CMD enum"]
10921 pub param1: f32,
10922 #[doc = "PARAM2, see MAV_CMD enum"]
10923 pub param2: f32,
10924 #[doc = "PARAM3, see MAV_CMD enum"]
10925 pub param3: f32,
10926 #[doc = "PARAM4, see MAV_CMD enum"]
10927 pub param4: f32,
10928 #[doc = "PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7"]
10929 pub x: i32,
10930 #[doc = "PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7"]
10931 pub y: i32,
10932 #[doc = "PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame)."]
10933 pub z: f32,
10934 #[doc = "The scheduled action for the mission item."]
10935 pub command: MavCmd,
10936 #[doc = "System ID"]
10937 pub target_system: u8,
10938 #[doc = "Component ID"]
10939 pub target_component: u8,
10940 #[doc = "The coordinate system of the COMMAND."]
10941 pub frame: MavFrame,
10942 #[doc = "Not used."]
10943 pub current: u8,
10944 #[doc = "Not used (set 0)."]
10945 pub autocontinue: u8,
10946}
10947impl COMMAND_INT_DATA {
10948 pub const ENCODED_LEN: usize = 35usize;
10949 pub const DEFAULT: Self = Self {
10950 param1: 0.0_f32,
10951 param2: 0.0_f32,
10952 param3: 0.0_f32,
10953 param4: 0.0_f32,
10954 x: 0_i32,
10955 y: 0_i32,
10956 z: 0.0_f32,
10957 command: MavCmd::DEFAULT,
10958 target_system: 0_u8,
10959 target_component: 0_u8,
10960 frame: MavFrame::DEFAULT,
10961 current: 0_u8,
10962 autocontinue: 0_u8,
10963 };
10964 #[cfg(feature = "arbitrary")]
10965 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10966 use arbitrary::{Arbitrary, Unstructured};
10967 let mut buf = [0u8; 1024];
10968 rng.fill_bytes(&mut buf);
10969 let mut unstructured = Unstructured::new(&buf);
10970 Self::arbitrary(&mut unstructured).unwrap_or_default()
10971 }
10972}
10973impl Default for COMMAND_INT_DATA {
10974 fn default() -> Self {
10975 Self::DEFAULT.clone()
10976 }
10977}
10978impl MessageData for COMMAND_INT_DATA {
10979 type Message = MavMessage;
10980 const ID: u32 = 75u32;
10981 const NAME: &'static str = "COMMAND_INT";
10982 const EXTRA_CRC: u8 = 158u8;
10983 const ENCODED_LEN: usize = 35usize;
10984 fn deser(
10985 _version: MavlinkVersion,
10986 __input: &[u8],
10987 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10988 let avail_len = __input.len();
10989 let mut payload_buf = [0; Self::ENCODED_LEN];
10990 let mut buf = if avail_len < Self::ENCODED_LEN {
10991 payload_buf[0..avail_len].copy_from_slice(__input);
10992 Bytes::new(&payload_buf)
10993 } else {
10994 Bytes::new(__input)
10995 };
10996 let mut __struct = Self::default();
10997 __struct.param1 = buf.get_f32_le()?;
10998 __struct.param2 = buf.get_f32_le()?;
10999 __struct.param3 = buf.get_f32_le()?;
11000 __struct.param4 = buf.get_f32_le()?;
11001 __struct.x = buf.get_i32_le()?;
11002 __struct.y = buf.get_i32_le()?;
11003 __struct.z = buf.get_f32_le()?;
11004 let tmp = buf.get_u16_le()?;
11005 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
11006 ::mavlink_core::error::ParserError::InvalidEnum {
11007 enum_type: "MavCmd",
11008 value: tmp as u64,
11009 },
11010 )?;
11011 __struct.target_system = buf.get_u8()?;
11012 __struct.target_component = buf.get_u8()?;
11013 let tmp = buf.get_u8()?;
11014 __struct.frame =
11015 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11016 enum_type: "MavFrame",
11017 value: tmp as u64,
11018 })?;
11019 __struct.current = buf.get_u8()?;
11020 __struct.autocontinue = buf.get_u8()?;
11021 Ok(__struct)
11022 }
11023 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11024 let mut __tmp = BytesMut::new(bytes);
11025 #[allow(clippy::absurd_extreme_comparisons)]
11026 #[allow(unused_comparisons)]
11027 if __tmp.remaining() < Self::ENCODED_LEN {
11028 panic!(
11029 "buffer is too small (need {} bytes, but got {})",
11030 Self::ENCODED_LEN,
11031 __tmp.remaining(),
11032 )
11033 }
11034 __tmp.put_f32_le(self.param1);
11035 __tmp.put_f32_le(self.param2);
11036 __tmp.put_f32_le(self.param3);
11037 __tmp.put_f32_le(self.param4);
11038 __tmp.put_i32_le(self.x);
11039 __tmp.put_i32_le(self.y);
11040 __tmp.put_f32_le(self.z);
11041 __tmp.put_u16_le(self.command as u16);
11042 __tmp.put_u8(self.target_system);
11043 __tmp.put_u8(self.target_component);
11044 __tmp.put_u8(self.frame as u8);
11045 __tmp.put_u8(self.current);
11046 __tmp.put_u8(self.autocontinue);
11047 if matches!(version, MavlinkVersion::V2) {
11048 let len = __tmp.len();
11049 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11050 } else {
11051 __tmp.len()
11052 }
11053 }
11054}
11055#[doc = "Send a command with up to seven parameters to the MAV. COMMAND_INT is generally preferred when sending MAV_CMD commands that include positional information; it offers higher precision and allows the MAV_FRAME to be specified (which may otherwise be ambiguous, particularly for altitude). The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
11056#[doc = ""]
11057#[doc = "ID: 76"]
11058#[derive(Debug, Clone, PartialEq)]
11059#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11060#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11061#[cfg_attr(feature = "ts", derive(TS))]
11062#[cfg_attr(feature = "ts", ts(export))]
11063pub struct COMMAND_LONG_DATA {
11064 #[doc = "Parameter 1 (for the specific command)."]
11065 pub param1: f32,
11066 #[doc = "Parameter 2 (for the specific command)."]
11067 pub param2: f32,
11068 #[doc = "Parameter 3 (for the specific command)."]
11069 pub param3: f32,
11070 #[doc = "Parameter 4 (for the specific command)."]
11071 pub param4: f32,
11072 #[doc = "Parameter 5 (for the specific command)."]
11073 pub param5: f32,
11074 #[doc = "Parameter 6 (for the specific command)."]
11075 pub param6: f32,
11076 #[doc = "Parameter 7 (for the specific command)."]
11077 pub param7: f32,
11078 #[doc = "Command ID (of command to send)."]
11079 pub command: MavCmd,
11080 #[doc = "System which should execute the command"]
11081 pub target_system: u8,
11082 #[doc = "Component which should execute the command, 0 for all components"]
11083 pub target_component: u8,
11084 #[doc = "0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)"]
11085 pub confirmation: u8,
11086}
11087impl COMMAND_LONG_DATA {
11088 pub const ENCODED_LEN: usize = 33usize;
11089 pub const DEFAULT: Self = Self {
11090 param1: 0.0_f32,
11091 param2: 0.0_f32,
11092 param3: 0.0_f32,
11093 param4: 0.0_f32,
11094 param5: 0.0_f32,
11095 param6: 0.0_f32,
11096 param7: 0.0_f32,
11097 command: MavCmd::DEFAULT,
11098 target_system: 0_u8,
11099 target_component: 0_u8,
11100 confirmation: 0_u8,
11101 };
11102 #[cfg(feature = "arbitrary")]
11103 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11104 use arbitrary::{Arbitrary, Unstructured};
11105 let mut buf = [0u8; 1024];
11106 rng.fill_bytes(&mut buf);
11107 let mut unstructured = Unstructured::new(&buf);
11108 Self::arbitrary(&mut unstructured).unwrap_or_default()
11109 }
11110}
11111impl Default for COMMAND_LONG_DATA {
11112 fn default() -> Self {
11113 Self::DEFAULT.clone()
11114 }
11115}
11116impl MessageData for COMMAND_LONG_DATA {
11117 type Message = MavMessage;
11118 const ID: u32 = 76u32;
11119 const NAME: &'static str = "COMMAND_LONG";
11120 const EXTRA_CRC: u8 = 152u8;
11121 const ENCODED_LEN: usize = 33usize;
11122 fn deser(
11123 _version: MavlinkVersion,
11124 __input: &[u8],
11125 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11126 let avail_len = __input.len();
11127 let mut payload_buf = [0; Self::ENCODED_LEN];
11128 let mut buf = if avail_len < Self::ENCODED_LEN {
11129 payload_buf[0..avail_len].copy_from_slice(__input);
11130 Bytes::new(&payload_buf)
11131 } else {
11132 Bytes::new(__input)
11133 };
11134 let mut __struct = Self::default();
11135 __struct.param1 = buf.get_f32_le()?;
11136 __struct.param2 = buf.get_f32_le()?;
11137 __struct.param3 = buf.get_f32_le()?;
11138 __struct.param4 = buf.get_f32_le()?;
11139 __struct.param5 = buf.get_f32_le()?;
11140 __struct.param6 = buf.get_f32_le()?;
11141 __struct.param7 = buf.get_f32_le()?;
11142 let tmp = buf.get_u16_le()?;
11143 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
11144 ::mavlink_core::error::ParserError::InvalidEnum {
11145 enum_type: "MavCmd",
11146 value: tmp as u64,
11147 },
11148 )?;
11149 __struct.target_system = buf.get_u8()?;
11150 __struct.target_component = buf.get_u8()?;
11151 __struct.confirmation = buf.get_u8()?;
11152 Ok(__struct)
11153 }
11154 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11155 let mut __tmp = BytesMut::new(bytes);
11156 #[allow(clippy::absurd_extreme_comparisons)]
11157 #[allow(unused_comparisons)]
11158 if __tmp.remaining() < Self::ENCODED_LEN {
11159 panic!(
11160 "buffer is too small (need {} bytes, but got {})",
11161 Self::ENCODED_LEN,
11162 __tmp.remaining(),
11163 )
11164 }
11165 __tmp.put_f32_le(self.param1);
11166 __tmp.put_f32_le(self.param2);
11167 __tmp.put_f32_le(self.param3);
11168 __tmp.put_f32_le(self.param4);
11169 __tmp.put_f32_le(self.param5);
11170 __tmp.put_f32_le(self.param6);
11171 __tmp.put_f32_le(self.param7);
11172 __tmp.put_u16_le(self.command as u16);
11173 __tmp.put_u8(self.target_system);
11174 __tmp.put_u8(self.target_component);
11175 __tmp.put_u8(self.confirmation);
11176 if matches!(version, MavlinkVersion::V2) {
11177 let len = __tmp.len();
11178 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11179 } else {
11180 __tmp.len()
11181 }
11182 }
11183}
11184#[deprecated = " See `COMPONENT_METADATA` (Deprecated since 2022-04)"]
11185#[doc = "Component information message, which may be requested using MAV_CMD_REQUEST_MESSAGE."]
11186#[doc = ""]
11187#[doc = "ID: 395"]
11188#[derive(Debug, Clone, PartialEq)]
11189#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11190#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11191#[cfg_attr(feature = "ts", derive(TS))]
11192#[cfg_attr(feature = "ts", ts(export))]
11193pub struct COMPONENT_INFORMATION_DATA {
11194 #[doc = "Timestamp (time since system boot)."]
11195 pub time_boot_ms: u32,
11196 #[doc = "CRC32 of the general metadata file (general_metadata_uri)."]
11197 pub general_metadata_file_crc: u32,
11198 #[doc = "CRC32 of peripherals metadata file (peripherals_metadata_uri)."]
11199 pub peripherals_metadata_file_crc: u32,
11200 #[doc = "MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated."]
11201 #[cfg_attr(feature = "ts", ts(type = "string"))]
11202 pub general_metadata_uri: CharArray<100>,
11203 #[doc = "(Optional) MAVLink FTP URI for the peripherals metadata file (COMP_METADATA_TYPE_PERIPHERALS), which may be compressed with xz. This contains data about \"attached components\" such as UAVCAN nodes. The peripherals are in a separate file because the information must be generated dynamically at runtime. The string needs to be zero terminated."]
11204 #[cfg_attr(feature = "ts", ts(type = "string"))]
11205 pub peripherals_metadata_uri: CharArray<100>,
11206}
11207impl COMPONENT_INFORMATION_DATA {
11208 pub const ENCODED_LEN: usize = 212usize;
11209 pub const DEFAULT: Self = Self {
11210 time_boot_ms: 0_u32,
11211 general_metadata_file_crc: 0_u32,
11212 peripherals_metadata_file_crc: 0_u32,
11213 general_metadata_uri: CharArray::new([0_u8; 100usize]),
11214 peripherals_metadata_uri: CharArray::new([0_u8; 100usize]),
11215 };
11216 #[cfg(feature = "arbitrary")]
11217 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11218 use arbitrary::{Arbitrary, Unstructured};
11219 let mut buf = [0u8; 1024];
11220 rng.fill_bytes(&mut buf);
11221 let mut unstructured = Unstructured::new(&buf);
11222 Self::arbitrary(&mut unstructured).unwrap_or_default()
11223 }
11224}
11225impl Default for COMPONENT_INFORMATION_DATA {
11226 fn default() -> Self {
11227 Self::DEFAULT.clone()
11228 }
11229}
11230impl MessageData for COMPONENT_INFORMATION_DATA {
11231 type Message = MavMessage;
11232 const ID: u32 = 395u32;
11233 const NAME: &'static str = "COMPONENT_INFORMATION";
11234 const EXTRA_CRC: u8 = 0u8;
11235 const ENCODED_LEN: usize = 212usize;
11236 fn deser(
11237 _version: MavlinkVersion,
11238 __input: &[u8],
11239 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11240 let avail_len = __input.len();
11241 let mut payload_buf = [0; Self::ENCODED_LEN];
11242 let mut buf = if avail_len < Self::ENCODED_LEN {
11243 payload_buf[0..avail_len].copy_from_slice(__input);
11244 Bytes::new(&payload_buf)
11245 } else {
11246 Bytes::new(__input)
11247 };
11248 let mut __struct = Self::default();
11249 __struct.time_boot_ms = buf.get_u32_le()?;
11250 __struct.general_metadata_file_crc = buf.get_u32_le()?;
11251 __struct.peripherals_metadata_file_crc = buf.get_u32_le()?;
11252 let mut tmp = [0_u8; 100usize];
11253 for v in &mut tmp {
11254 *v = buf.get_u8()?;
11255 }
11256 __struct.general_metadata_uri = CharArray::new(tmp);
11257 let mut tmp = [0_u8; 100usize];
11258 for v in &mut tmp {
11259 *v = buf.get_u8()?;
11260 }
11261 __struct.peripherals_metadata_uri = CharArray::new(tmp);
11262 Ok(__struct)
11263 }
11264 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11265 let mut __tmp = BytesMut::new(bytes);
11266 #[allow(clippy::absurd_extreme_comparisons)]
11267 #[allow(unused_comparisons)]
11268 if __tmp.remaining() < Self::ENCODED_LEN {
11269 panic!(
11270 "buffer is too small (need {} bytes, but got {})",
11271 Self::ENCODED_LEN,
11272 __tmp.remaining(),
11273 )
11274 }
11275 __tmp.put_u32_le(self.time_boot_ms);
11276 __tmp.put_u32_le(self.general_metadata_file_crc);
11277 __tmp.put_u32_le(self.peripherals_metadata_file_crc);
11278 for val in &self.general_metadata_uri {
11279 __tmp.put_u8(*val);
11280 }
11281 for val in &self.peripherals_metadata_uri {
11282 __tmp.put_u8(*val);
11283 }
11284 if matches!(version, MavlinkVersion::V2) {
11285 let len = __tmp.len();
11286 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11287 } else {
11288 __tmp.len()
11289 }
11290 }
11291}
11292#[doc = "Basic component information data. Should be requested using MAV_CMD_REQUEST_MESSAGE on startup, or when required."]
11293#[doc = ""]
11294#[doc = "ID: 396"]
11295#[derive(Debug, Clone, PartialEq)]
11296#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11297#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11298#[cfg_attr(feature = "ts", derive(TS))]
11299#[cfg_attr(feature = "ts", ts(export))]
11300pub struct COMPONENT_INFORMATION_BASIC_DATA {
11301 #[doc = "Component capability flags"]
11302 pub capabilities: MavProtocolCapability,
11303 #[doc = "Timestamp (time since system boot)."]
11304 pub time_boot_ms: u32,
11305 #[doc = "Date of manufacture as a UNIX Epoch time (since 1.1.1970) in seconds."]
11306 pub time_manufacture_s: u32,
11307 #[doc = "Name of the component vendor. Needs to be zero terminated. The field is optional and can be empty/all zeros."]
11308 #[cfg_attr(feature = "ts", ts(type = "string"))]
11309 pub vendor_name: CharArray<32>,
11310 #[doc = "Name of the component model. Needs to be zero terminated. The field is optional and can be empty/all zeros."]
11311 #[cfg_attr(feature = "ts", ts(type = "string"))]
11312 pub model_name: CharArray<32>,
11313 #[doc = "Software version. The recommended format is SEMVER: 'major.minor.patch' (any format may be used). The field must be zero terminated if it has a value. The field is optional and can be empty/all zeros."]
11314 #[cfg_attr(feature = "ts", ts(type = "string"))]
11315 pub software_version: CharArray<24>,
11316 #[doc = "Hardware version. The recommended format is SEMVER: 'major.minor.patch' (any format may be used). The field must be zero terminated if it has a value. The field is optional and can be empty/all zeros."]
11317 #[cfg_attr(feature = "ts", ts(type = "string"))]
11318 pub hardware_version: CharArray<24>,
11319 #[doc = "Hardware serial number. The field must be zero terminated if it has a value. The field is optional and can be empty/all zeros."]
11320 #[cfg_attr(feature = "ts", ts(type = "string"))]
11321 pub serial_number: CharArray<32>,
11322}
11323impl COMPONENT_INFORMATION_BASIC_DATA {
11324 pub const ENCODED_LEN: usize = 160usize;
11325 pub const DEFAULT: Self = Self {
11326 capabilities: MavProtocolCapability::DEFAULT,
11327 time_boot_ms: 0_u32,
11328 time_manufacture_s: 0_u32,
11329 vendor_name: CharArray::new([0_u8; 32usize]),
11330 model_name: CharArray::new([0_u8; 32usize]),
11331 software_version: CharArray::new([0_u8; 24usize]),
11332 hardware_version: CharArray::new([0_u8; 24usize]),
11333 serial_number: CharArray::new([0_u8; 32usize]),
11334 };
11335 #[cfg(feature = "arbitrary")]
11336 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11337 use arbitrary::{Arbitrary, Unstructured};
11338 let mut buf = [0u8; 1024];
11339 rng.fill_bytes(&mut buf);
11340 let mut unstructured = Unstructured::new(&buf);
11341 Self::arbitrary(&mut unstructured).unwrap_or_default()
11342 }
11343}
11344impl Default for COMPONENT_INFORMATION_BASIC_DATA {
11345 fn default() -> Self {
11346 Self::DEFAULT.clone()
11347 }
11348}
11349impl MessageData for COMPONENT_INFORMATION_BASIC_DATA {
11350 type Message = MavMessage;
11351 const ID: u32 = 396u32;
11352 const NAME: &'static str = "COMPONENT_INFORMATION_BASIC";
11353 const EXTRA_CRC: u8 = 50u8;
11354 const ENCODED_LEN: usize = 160usize;
11355 fn deser(
11356 _version: MavlinkVersion,
11357 __input: &[u8],
11358 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11359 let avail_len = __input.len();
11360 let mut payload_buf = [0; Self::ENCODED_LEN];
11361 let mut buf = if avail_len < Self::ENCODED_LEN {
11362 payload_buf[0..avail_len].copy_from_slice(__input);
11363 Bytes::new(&payload_buf)
11364 } else {
11365 Bytes::new(__input)
11366 };
11367 let mut __struct = Self::default();
11368 let tmp = buf.get_u64_le()?;
11369 __struct.capabilities = MavProtocolCapability::from_bits(
11370 tmp as <MavProtocolCapability as Flags>::Bits,
11371 )
11372 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
11373 flag_type: "MavProtocolCapability",
11374 value: tmp as u64,
11375 })?;
11376 __struct.time_boot_ms = buf.get_u32_le()?;
11377 __struct.time_manufacture_s = buf.get_u32_le()?;
11378 let mut tmp = [0_u8; 32usize];
11379 for v in &mut tmp {
11380 *v = buf.get_u8()?;
11381 }
11382 __struct.vendor_name = CharArray::new(tmp);
11383 let mut tmp = [0_u8; 32usize];
11384 for v in &mut tmp {
11385 *v = buf.get_u8()?;
11386 }
11387 __struct.model_name = CharArray::new(tmp);
11388 let mut tmp = [0_u8; 24usize];
11389 for v in &mut tmp {
11390 *v = buf.get_u8()?;
11391 }
11392 __struct.software_version = CharArray::new(tmp);
11393 let mut tmp = [0_u8; 24usize];
11394 for v in &mut tmp {
11395 *v = buf.get_u8()?;
11396 }
11397 __struct.hardware_version = CharArray::new(tmp);
11398 let mut tmp = [0_u8; 32usize];
11399 for v in &mut tmp {
11400 *v = buf.get_u8()?;
11401 }
11402 __struct.serial_number = CharArray::new(tmp);
11403 Ok(__struct)
11404 }
11405 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11406 let mut __tmp = BytesMut::new(bytes);
11407 #[allow(clippy::absurd_extreme_comparisons)]
11408 #[allow(unused_comparisons)]
11409 if __tmp.remaining() < Self::ENCODED_LEN {
11410 panic!(
11411 "buffer is too small (need {} bytes, but got {})",
11412 Self::ENCODED_LEN,
11413 __tmp.remaining(),
11414 )
11415 }
11416 __tmp.put_u64_le(self.capabilities.bits() as u64);
11417 __tmp.put_u32_le(self.time_boot_ms);
11418 __tmp.put_u32_le(self.time_manufacture_s);
11419 for val in &self.vendor_name {
11420 __tmp.put_u8(*val);
11421 }
11422 for val in &self.model_name {
11423 __tmp.put_u8(*val);
11424 }
11425 for val in &self.software_version {
11426 __tmp.put_u8(*val);
11427 }
11428 for val in &self.hardware_version {
11429 __tmp.put_u8(*val);
11430 }
11431 for val in &self.serial_number {
11432 __tmp.put_u8(*val);
11433 }
11434 if matches!(version, MavlinkVersion::V2) {
11435 let len = __tmp.len();
11436 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11437 } else {
11438 __tmp.len()
11439 }
11440 }
11441}
11442#[doc = "Component metadata message, which may be requested using MAV_CMD_REQUEST_MESSAGE. This contains the MAVLink FTP URI and CRC for the component's general metadata file. The file must be hosted on the component, and may be xz compressed. The file CRC can be used for file caching. The general metadata file can be read to get the locations of other metadata files (COMP_METADATA_TYPE) and translations, which may be hosted either on the vehicle or the internet. For more information see: <https://mavlink.io/en/services/component_information.html>. Note: Camera components should use CAMERA_INFORMATION instead, and autopilots may use both this message and AUTOPILOT_VERSION."]
11443#[doc = ""]
11444#[doc = "ID: 397"]
11445#[derive(Debug, Clone, PartialEq)]
11446#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11447#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11448#[cfg_attr(feature = "ts", derive(TS))]
11449#[cfg_attr(feature = "ts", ts(export))]
11450pub struct COMPONENT_METADATA_DATA {
11451 #[doc = "Timestamp (time since system boot)."]
11452 pub time_boot_ms: u32,
11453 #[doc = "CRC32 of the general metadata file."]
11454 pub file_crc: u32,
11455 #[doc = "MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated."]
11456 #[cfg_attr(feature = "ts", ts(type = "string"))]
11457 pub uri: CharArray<100>,
11458}
11459impl COMPONENT_METADATA_DATA {
11460 pub const ENCODED_LEN: usize = 108usize;
11461 pub const DEFAULT: Self = Self {
11462 time_boot_ms: 0_u32,
11463 file_crc: 0_u32,
11464 uri: CharArray::new([0_u8; 100usize]),
11465 };
11466 #[cfg(feature = "arbitrary")]
11467 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11468 use arbitrary::{Arbitrary, Unstructured};
11469 let mut buf = [0u8; 1024];
11470 rng.fill_bytes(&mut buf);
11471 let mut unstructured = Unstructured::new(&buf);
11472 Self::arbitrary(&mut unstructured).unwrap_or_default()
11473 }
11474}
11475impl Default for COMPONENT_METADATA_DATA {
11476 fn default() -> Self {
11477 Self::DEFAULT.clone()
11478 }
11479}
11480impl MessageData for COMPONENT_METADATA_DATA {
11481 type Message = MavMessage;
11482 const ID: u32 = 397u32;
11483 const NAME: &'static str = "COMPONENT_METADATA";
11484 const EXTRA_CRC: u8 = 182u8;
11485 const ENCODED_LEN: usize = 108usize;
11486 fn deser(
11487 _version: MavlinkVersion,
11488 __input: &[u8],
11489 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11490 let avail_len = __input.len();
11491 let mut payload_buf = [0; Self::ENCODED_LEN];
11492 let mut buf = if avail_len < Self::ENCODED_LEN {
11493 payload_buf[0..avail_len].copy_from_slice(__input);
11494 Bytes::new(&payload_buf)
11495 } else {
11496 Bytes::new(__input)
11497 };
11498 let mut __struct = Self::default();
11499 __struct.time_boot_ms = buf.get_u32_le()?;
11500 __struct.file_crc = buf.get_u32_le()?;
11501 let mut tmp = [0_u8; 100usize];
11502 for v in &mut tmp {
11503 *v = buf.get_u8()?;
11504 }
11505 __struct.uri = CharArray::new(tmp);
11506 Ok(__struct)
11507 }
11508 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11509 let mut __tmp = BytesMut::new(bytes);
11510 #[allow(clippy::absurd_extreme_comparisons)]
11511 #[allow(unused_comparisons)]
11512 if __tmp.remaining() < Self::ENCODED_LEN {
11513 panic!(
11514 "buffer is too small (need {} bytes, but got {})",
11515 Self::ENCODED_LEN,
11516 __tmp.remaining(),
11517 )
11518 }
11519 __tmp.put_u32_le(self.time_boot_ms);
11520 __tmp.put_u32_le(self.file_crc);
11521 for val in &self.uri {
11522 __tmp.put_u8(*val);
11523 }
11524 if matches!(version, MavlinkVersion::V2) {
11525 let len = __tmp.len();
11526 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11527 } else {
11528 __tmp.len()
11529 }
11530 }
11531}
11532#[doc = "The smoothed, monotonic system state used to feed the control loops of the system."]
11533#[doc = ""]
11534#[doc = "ID: 146"]
11535#[derive(Debug, Clone, PartialEq)]
11536#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11537#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11538#[cfg_attr(feature = "ts", derive(TS))]
11539#[cfg_attr(feature = "ts", ts(export))]
11540pub struct CONTROL_SYSTEM_STATE_DATA {
11541 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
11542 pub time_usec: u64,
11543 #[doc = "X acceleration in body frame"]
11544 pub x_acc: f32,
11545 #[doc = "Y acceleration in body frame"]
11546 pub y_acc: f32,
11547 #[doc = "Z acceleration in body frame"]
11548 pub z_acc: f32,
11549 #[doc = "X velocity in body frame"]
11550 pub x_vel: f32,
11551 #[doc = "Y velocity in body frame"]
11552 pub y_vel: f32,
11553 #[doc = "Z velocity in body frame"]
11554 pub z_vel: f32,
11555 #[doc = "X position in local frame"]
11556 pub x_pos: f32,
11557 #[doc = "Y position in local frame"]
11558 pub y_pos: f32,
11559 #[doc = "Z position in local frame"]
11560 pub z_pos: f32,
11561 #[doc = "Airspeed, set to -1 if unknown"]
11562 pub airspeed: f32,
11563 #[doc = "Variance of body velocity estimate"]
11564 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11565 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
11566 pub vel_variance: [f32; 3],
11567 #[doc = "Variance in local position"]
11568 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11569 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
11570 pub pos_variance: [f32; 3],
11571 #[doc = "The attitude, represented as Quaternion"]
11572 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11573 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
11574 pub q: [f32; 4],
11575 #[doc = "Angular rate in roll axis"]
11576 pub roll_rate: f32,
11577 #[doc = "Angular rate in pitch axis"]
11578 pub pitch_rate: f32,
11579 #[doc = "Angular rate in yaw axis"]
11580 pub yaw_rate: f32,
11581}
11582impl CONTROL_SYSTEM_STATE_DATA {
11583 pub const ENCODED_LEN: usize = 100usize;
11584 pub const DEFAULT: Self = Self {
11585 time_usec: 0_u64,
11586 x_acc: 0.0_f32,
11587 y_acc: 0.0_f32,
11588 z_acc: 0.0_f32,
11589 x_vel: 0.0_f32,
11590 y_vel: 0.0_f32,
11591 z_vel: 0.0_f32,
11592 x_pos: 0.0_f32,
11593 y_pos: 0.0_f32,
11594 z_pos: 0.0_f32,
11595 airspeed: 0.0_f32,
11596 vel_variance: [0.0_f32; 3usize],
11597 pos_variance: [0.0_f32; 3usize],
11598 q: [0.0_f32; 4usize],
11599 roll_rate: 0.0_f32,
11600 pitch_rate: 0.0_f32,
11601 yaw_rate: 0.0_f32,
11602 };
11603 #[cfg(feature = "arbitrary")]
11604 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11605 use arbitrary::{Arbitrary, Unstructured};
11606 let mut buf = [0u8; 1024];
11607 rng.fill_bytes(&mut buf);
11608 let mut unstructured = Unstructured::new(&buf);
11609 Self::arbitrary(&mut unstructured).unwrap_or_default()
11610 }
11611}
11612impl Default for CONTROL_SYSTEM_STATE_DATA {
11613 fn default() -> Self {
11614 Self::DEFAULT.clone()
11615 }
11616}
11617impl MessageData for CONTROL_SYSTEM_STATE_DATA {
11618 type Message = MavMessage;
11619 const ID: u32 = 146u32;
11620 const NAME: &'static str = "CONTROL_SYSTEM_STATE";
11621 const EXTRA_CRC: u8 = 103u8;
11622 const ENCODED_LEN: usize = 100usize;
11623 fn deser(
11624 _version: MavlinkVersion,
11625 __input: &[u8],
11626 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11627 let avail_len = __input.len();
11628 let mut payload_buf = [0; Self::ENCODED_LEN];
11629 let mut buf = if avail_len < Self::ENCODED_LEN {
11630 payload_buf[0..avail_len].copy_from_slice(__input);
11631 Bytes::new(&payload_buf)
11632 } else {
11633 Bytes::new(__input)
11634 };
11635 let mut __struct = Self::default();
11636 __struct.time_usec = buf.get_u64_le()?;
11637 __struct.x_acc = buf.get_f32_le()?;
11638 __struct.y_acc = buf.get_f32_le()?;
11639 __struct.z_acc = buf.get_f32_le()?;
11640 __struct.x_vel = buf.get_f32_le()?;
11641 __struct.y_vel = buf.get_f32_le()?;
11642 __struct.z_vel = buf.get_f32_le()?;
11643 __struct.x_pos = buf.get_f32_le()?;
11644 __struct.y_pos = buf.get_f32_le()?;
11645 __struct.z_pos = buf.get_f32_le()?;
11646 __struct.airspeed = buf.get_f32_le()?;
11647 for v in &mut __struct.vel_variance {
11648 let val = buf.get_f32_le()?;
11649 *v = val;
11650 }
11651 for v in &mut __struct.pos_variance {
11652 let val = buf.get_f32_le()?;
11653 *v = val;
11654 }
11655 for v in &mut __struct.q {
11656 let val = buf.get_f32_le()?;
11657 *v = val;
11658 }
11659 __struct.roll_rate = buf.get_f32_le()?;
11660 __struct.pitch_rate = buf.get_f32_le()?;
11661 __struct.yaw_rate = buf.get_f32_le()?;
11662 Ok(__struct)
11663 }
11664 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11665 let mut __tmp = BytesMut::new(bytes);
11666 #[allow(clippy::absurd_extreme_comparisons)]
11667 #[allow(unused_comparisons)]
11668 if __tmp.remaining() < Self::ENCODED_LEN {
11669 panic!(
11670 "buffer is too small (need {} bytes, but got {})",
11671 Self::ENCODED_LEN,
11672 __tmp.remaining(),
11673 )
11674 }
11675 __tmp.put_u64_le(self.time_usec);
11676 __tmp.put_f32_le(self.x_acc);
11677 __tmp.put_f32_le(self.y_acc);
11678 __tmp.put_f32_le(self.z_acc);
11679 __tmp.put_f32_le(self.x_vel);
11680 __tmp.put_f32_le(self.y_vel);
11681 __tmp.put_f32_le(self.z_vel);
11682 __tmp.put_f32_le(self.x_pos);
11683 __tmp.put_f32_le(self.y_pos);
11684 __tmp.put_f32_le(self.z_pos);
11685 __tmp.put_f32_le(self.airspeed);
11686 for val in &self.vel_variance {
11687 __tmp.put_f32_le(*val);
11688 }
11689 for val in &self.pos_variance {
11690 __tmp.put_f32_le(*val);
11691 }
11692 for val in &self.q {
11693 __tmp.put_f32_le(*val);
11694 }
11695 __tmp.put_f32_le(self.roll_rate);
11696 __tmp.put_f32_le(self.pitch_rate);
11697 __tmp.put_f32_le(self.yaw_rate);
11698 if matches!(version, MavlinkVersion::V2) {
11699 let len = __tmp.len();
11700 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11701 } else {
11702 __tmp.len()
11703 }
11704 }
11705}
11706#[doc = "Regular broadcast for the current latest event sequence number for a component. This is used to check for dropped events."]
11707#[doc = ""]
11708#[doc = "ID: 411"]
11709#[derive(Debug, Clone, PartialEq)]
11710#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11711#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11712#[cfg_attr(feature = "ts", derive(TS))]
11713#[cfg_attr(feature = "ts", ts(export))]
11714pub struct CURRENT_EVENT_SEQUENCE_DATA {
11715 #[doc = "Sequence number."]
11716 pub sequence: u16,
11717 #[doc = "Flag bitset."]
11718 pub flags: MavEventCurrentSequenceFlags,
11719}
11720impl CURRENT_EVENT_SEQUENCE_DATA {
11721 pub const ENCODED_LEN: usize = 3usize;
11722 pub const DEFAULT: Self = Self {
11723 sequence: 0_u16,
11724 flags: MavEventCurrentSequenceFlags::DEFAULT,
11725 };
11726 #[cfg(feature = "arbitrary")]
11727 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11728 use arbitrary::{Arbitrary, Unstructured};
11729 let mut buf = [0u8; 1024];
11730 rng.fill_bytes(&mut buf);
11731 let mut unstructured = Unstructured::new(&buf);
11732 Self::arbitrary(&mut unstructured).unwrap_or_default()
11733 }
11734}
11735impl Default for CURRENT_EVENT_SEQUENCE_DATA {
11736 fn default() -> Self {
11737 Self::DEFAULT.clone()
11738 }
11739}
11740impl MessageData for CURRENT_EVENT_SEQUENCE_DATA {
11741 type Message = MavMessage;
11742 const ID: u32 = 411u32;
11743 const NAME: &'static str = "CURRENT_EVENT_SEQUENCE";
11744 const EXTRA_CRC: u8 = 106u8;
11745 const ENCODED_LEN: usize = 3usize;
11746 fn deser(
11747 _version: MavlinkVersion,
11748 __input: &[u8],
11749 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11750 let avail_len = __input.len();
11751 let mut payload_buf = [0; Self::ENCODED_LEN];
11752 let mut buf = if avail_len < Self::ENCODED_LEN {
11753 payload_buf[0..avail_len].copy_from_slice(__input);
11754 Bytes::new(&payload_buf)
11755 } else {
11756 Bytes::new(__input)
11757 };
11758 let mut __struct = Self::default();
11759 __struct.sequence = buf.get_u16_le()?;
11760 let tmp = buf.get_u8()?;
11761 __struct.flags =
11762 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11763 enum_type: "MavEventCurrentSequenceFlags",
11764 value: tmp as u64,
11765 })?;
11766 Ok(__struct)
11767 }
11768 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11769 let mut __tmp = BytesMut::new(bytes);
11770 #[allow(clippy::absurd_extreme_comparisons)]
11771 #[allow(unused_comparisons)]
11772 if __tmp.remaining() < Self::ENCODED_LEN {
11773 panic!(
11774 "buffer is too small (need {} bytes, but got {})",
11775 Self::ENCODED_LEN,
11776 __tmp.remaining(),
11777 )
11778 }
11779 __tmp.put_u16_le(self.sequence);
11780 __tmp.put_u8(self.flags as u8);
11781 if matches!(version, MavlinkVersion::V2) {
11782 let len = __tmp.len();
11783 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11784 } else {
11785 __tmp.len()
11786 }
11787 }
11788}
11789#[doc = "Get the current mode. This should be emitted on any mode change, and broadcast at low rate (nominally 0.5 Hz). It may be requested using MAV_CMD_REQUEST_MESSAGE. See <https://mavlink.io/en/services/standard_modes.html>."]
11790#[doc = ""]
11791#[doc = "ID: 436"]
11792#[derive(Debug, Clone, PartialEq)]
11793#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11794#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11795#[cfg_attr(feature = "ts", derive(TS))]
11796#[cfg_attr(feature = "ts", ts(export))]
11797pub struct CURRENT_MODE_DATA {
11798 #[doc = "A bitfield for use for autopilot-specific flags"]
11799 pub custom_mode: u32,
11800 #[doc = "The custom_mode of the mode that was last commanded by the user (for example, with MAV_CMD_DO_SET_STANDARD_MODE, MAV_CMD_DO_SET_MODE or via RC). This should usually be the same as custom_mode. It will be different if the vehicle is unable to enter the intended mode, or has left that mode due to a failsafe condition. 0 indicates the intended custom mode is unknown/not supplied"]
11801 pub intended_custom_mode: u32,
11802 #[doc = "Standard mode."]
11803 pub standard_mode: MavStandardMode,
11804}
11805impl CURRENT_MODE_DATA {
11806 pub const ENCODED_LEN: usize = 9usize;
11807 pub const DEFAULT: Self = Self {
11808 custom_mode: 0_u32,
11809 intended_custom_mode: 0_u32,
11810 standard_mode: MavStandardMode::DEFAULT,
11811 };
11812 #[cfg(feature = "arbitrary")]
11813 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11814 use arbitrary::{Arbitrary, Unstructured};
11815 let mut buf = [0u8; 1024];
11816 rng.fill_bytes(&mut buf);
11817 let mut unstructured = Unstructured::new(&buf);
11818 Self::arbitrary(&mut unstructured).unwrap_or_default()
11819 }
11820}
11821impl Default for CURRENT_MODE_DATA {
11822 fn default() -> Self {
11823 Self::DEFAULT.clone()
11824 }
11825}
11826impl MessageData for CURRENT_MODE_DATA {
11827 type Message = MavMessage;
11828 const ID: u32 = 436u32;
11829 const NAME: &'static str = "CURRENT_MODE";
11830 const EXTRA_CRC: u8 = 193u8;
11831 const ENCODED_LEN: usize = 9usize;
11832 fn deser(
11833 _version: MavlinkVersion,
11834 __input: &[u8],
11835 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11836 let avail_len = __input.len();
11837 let mut payload_buf = [0; Self::ENCODED_LEN];
11838 let mut buf = if avail_len < Self::ENCODED_LEN {
11839 payload_buf[0..avail_len].copy_from_slice(__input);
11840 Bytes::new(&payload_buf)
11841 } else {
11842 Bytes::new(__input)
11843 };
11844 let mut __struct = Self::default();
11845 __struct.custom_mode = buf.get_u32_le()?;
11846 __struct.intended_custom_mode = buf.get_u32_le()?;
11847 let tmp = buf.get_u8()?;
11848 __struct.standard_mode =
11849 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11850 enum_type: "MavStandardMode",
11851 value: tmp as u64,
11852 })?;
11853 Ok(__struct)
11854 }
11855 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11856 let mut __tmp = BytesMut::new(bytes);
11857 #[allow(clippy::absurd_extreme_comparisons)]
11858 #[allow(unused_comparisons)]
11859 if __tmp.remaining() < Self::ENCODED_LEN {
11860 panic!(
11861 "buffer is too small (need {} bytes, but got {})",
11862 Self::ENCODED_LEN,
11863 __tmp.remaining(),
11864 )
11865 }
11866 __tmp.put_u32_le(self.custom_mode);
11867 __tmp.put_u32_le(self.intended_custom_mode);
11868 __tmp.put_u8(self.standard_mode as u8);
11869 if matches!(version, MavlinkVersion::V2) {
11870 let len = __tmp.len();
11871 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11872 } else {
11873 __tmp.len()
11874 }
11875 }
11876}
11877#[deprecated = " See `MESSAGE_INTERVAL` (Deprecated since 2015-08)"]
11878#[doc = "Data stream status information."]
11879#[doc = ""]
11880#[doc = "ID: 67"]
11881#[derive(Debug, Clone, PartialEq)]
11882#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11883#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11884#[cfg_attr(feature = "ts", derive(TS))]
11885#[cfg_attr(feature = "ts", ts(export))]
11886pub struct DATA_STREAM_DATA {
11887 #[doc = "The message rate"]
11888 pub message_rate: u16,
11889 #[doc = "The ID of the requested data stream"]
11890 pub stream_id: u8,
11891 #[doc = "1 stream is enabled, 0 stream is stopped."]
11892 pub on_off: u8,
11893}
11894impl DATA_STREAM_DATA {
11895 pub const ENCODED_LEN: usize = 4usize;
11896 pub const DEFAULT: Self = Self {
11897 message_rate: 0_u16,
11898 stream_id: 0_u8,
11899 on_off: 0_u8,
11900 };
11901 #[cfg(feature = "arbitrary")]
11902 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11903 use arbitrary::{Arbitrary, Unstructured};
11904 let mut buf = [0u8; 1024];
11905 rng.fill_bytes(&mut buf);
11906 let mut unstructured = Unstructured::new(&buf);
11907 Self::arbitrary(&mut unstructured).unwrap_or_default()
11908 }
11909}
11910impl Default for DATA_STREAM_DATA {
11911 fn default() -> Self {
11912 Self::DEFAULT.clone()
11913 }
11914}
11915impl MessageData for DATA_STREAM_DATA {
11916 type Message = MavMessage;
11917 const ID: u32 = 67u32;
11918 const NAME: &'static str = "DATA_STREAM";
11919 const EXTRA_CRC: u8 = 21u8;
11920 const ENCODED_LEN: usize = 4usize;
11921 fn deser(
11922 _version: MavlinkVersion,
11923 __input: &[u8],
11924 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11925 let avail_len = __input.len();
11926 let mut payload_buf = [0; Self::ENCODED_LEN];
11927 let mut buf = if avail_len < Self::ENCODED_LEN {
11928 payload_buf[0..avail_len].copy_from_slice(__input);
11929 Bytes::new(&payload_buf)
11930 } else {
11931 Bytes::new(__input)
11932 };
11933 let mut __struct = Self::default();
11934 __struct.message_rate = buf.get_u16_le()?;
11935 __struct.stream_id = buf.get_u8()?;
11936 __struct.on_off = buf.get_u8()?;
11937 Ok(__struct)
11938 }
11939 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11940 let mut __tmp = BytesMut::new(bytes);
11941 #[allow(clippy::absurd_extreme_comparisons)]
11942 #[allow(unused_comparisons)]
11943 if __tmp.remaining() < Self::ENCODED_LEN {
11944 panic!(
11945 "buffer is too small (need {} bytes, but got {})",
11946 Self::ENCODED_LEN,
11947 __tmp.remaining(),
11948 )
11949 }
11950 __tmp.put_u16_le(self.message_rate);
11951 __tmp.put_u8(self.stream_id);
11952 __tmp.put_u8(self.on_off);
11953 if matches!(version, MavlinkVersion::V2) {
11954 let len = __tmp.len();
11955 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11956 } else {
11957 __tmp.len()
11958 }
11959 }
11960}
11961#[doc = "Handshake message to initiate, control and stop image streaming when using the Image Transmission Protocol: <https://mavlink.io/en/services/image_transmission.html>."]
11962#[doc = ""]
11963#[doc = "ID: 130"]
11964#[derive(Debug, Clone, PartialEq)]
11965#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11966#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11967#[cfg_attr(feature = "ts", derive(TS))]
11968#[cfg_attr(feature = "ts", ts(export))]
11969pub struct DATA_TRANSMISSION_HANDSHAKE_DATA {
11970 #[doc = "total data size (set on ACK only)."]
11971 pub size: u32,
11972 #[doc = "Width of a matrix or image."]
11973 pub width: u16,
11974 #[doc = "Height of a matrix or image."]
11975 pub height: u16,
11976 #[doc = "Number of packets being sent (set on ACK only)."]
11977 pub packets: u16,
11978 #[doc = "Type of requested/acknowledged data."]
11979 pub mavtype: MavlinkDataStreamType,
11980 #[doc = "Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)."]
11981 pub payload: u8,
11982 #[doc = "JPEG quality. Values: [1-100]."]
11983 pub jpg_quality: u8,
11984}
11985impl DATA_TRANSMISSION_HANDSHAKE_DATA {
11986 pub const ENCODED_LEN: usize = 13usize;
11987 pub const DEFAULT: Self = Self {
11988 size: 0_u32,
11989 width: 0_u16,
11990 height: 0_u16,
11991 packets: 0_u16,
11992 mavtype: MavlinkDataStreamType::DEFAULT,
11993 payload: 0_u8,
11994 jpg_quality: 0_u8,
11995 };
11996 #[cfg(feature = "arbitrary")]
11997 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11998 use arbitrary::{Arbitrary, Unstructured};
11999 let mut buf = [0u8; 1024];
12000 rng.fill_bytes(&mut buf);
12001 let mut unstructured = Unstructured::new(&buf);
12002 Self::arbitrary(&mut unstructured).unwrap_or_default()
12003 }
12004}
12005impl Default for DATA_TRANSMISSION_HANDSHAKE_DATA {
12006 fn default() -> Self {
12007 Self::DEFAULT.clone()
12008 }
12009}
12010impl MessageData for DATA_TRANSMISSION_HANDSHAKE_DATA {
12011 type Message = MavMessage;
12012 const ID: u32 = 130u32;
12013 const NAME: &'static str = "DATA_TRANSMISSION_HANDSHAKE";
12014 const EXTRA_CRC: u8 = 29u8;
12015 const ENCODED_LEN: usize = 13usize;
12016 fn deser(
12017 _version: MavlinkVersion,
12018 __input: &[u8],
12019 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12020 let avail_len = __input.len();
12021 let mut payload_buf = [0; Self::ENCODED_LEN];
12022 let mut buf = if avail_len < Self::ENCODED_LEN {
12023 payload_buf[0..avail_len].copy_from_slice(__input);
12024 Bytes::new(&payload_buf)
12025 } else {
12026 Bytes::new(__input)
12027 };
12028 let mut __struct = Self::default();
12029 __struct.size = buf.get_u32_le()?;
12030 __struct.width = buf.get_u16_le()?;
12031 __struct.height = buf.get_u16_le()?;
12032 __struct.packets = buf.get_u16_le()?;
12033 let tmp = buf.get_u8()?;
12034 __struct.mavtype =
12035 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
12036 enum_type: "MavlinkDataStreamType",
12037 value: tmp as u64,
12038 })?;
12039 __struct.payload = buf.get_u8()?;
12040 __struct.jpg_quality = buf.get_u8()?;
12041 Ok(__struct)
12042 }
12043 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12044 let mut __tmp = BytesMut::new(bytes);
12045 #[allow(clippy::absurd_extreme_comparisons)]
12046 #[allow(unused_comparisons)]
12047 if __tmp.remaining() < Self::ENCODED_LEN {
12048 panic!(
12049 "buffer is too small (need {} bytes, but got {})",
12050 Self::ENCODED_LEN,
12051 __tmp.remaining(),
12052 )
12053 }
12054 __tmp.put_u32_le(self.size);
12055 __tmp.put_u16_le(self.width);
12056 __tmp.put_u16_le(self.height);
12057 __tmp.put_u16_le(self.packets);
12058 __tmp.put_u8(self.mavtype as u8);
12059 __tmp.put_u8(self.payload);
12060 __tmp.put_u8(self.jpg_quality);
12061 if matches!(version, MavlinkVersion::V2) {
12062 let len = __tmp.len();
12063 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12064 } else {
12065 __tmp.len()
12066 }
12067 }
12068}
12069#[doc = "Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N."]
12070#[doc = ""]
12071#[doc = "ID: 254"]
12072#[derive(Debug, Clone, PartialEq)]
12073#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12074#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12075#[cfg_attr(feature = "ts", derive(TS))]
12076#[cfg_attr(feature = "ts", ts(export))]
12077pub struct DEBUG_DATA {
12078 #[doc = "Timestamp (time since system boot)."]
12079 pub time_boot_ms: u32,
12080 #[doc = "DEBUG value"]
12081 pub value: f32,
12082 #[doc = "index of debug variable"]
12083 pub ind: u8,
12084}
12085impl DEBUG_DATA {
12086 pub const ENCODED_LEN: usize = 9usize;
12087 pub const DEFAULT: Self = Self {
12088 time_boot_ms: 0_u32,
12089 value: 0.0_f32,
12090 ind: 0_u8,
12091 };
12092 #[cfg(feature = "arbitrary")]
12093 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12094 use arbitrary::{Arbitrary, Unstructured};
12095 let mut buf = [0u8; 1024];
12096 rng.fill_bytes(&mut buf);
12097 let mut unstructured = Unstructured::new(&buf);
12098 Self::arbitrary(&mut unstructured).unwrap_or_default()
12099 }
12100}
12101impl Default for DEBUG_DATA {
12102 fn default() -> Self {
12103 Self::DEFAULT.clone()
12104 }
12105}
12106impl MessageData for DEBUG_DATA {
12107 type Message = MavMessage;
12108 const ID: u32 = 254u32;
12109 const NAME: &'static str = "DEBUG";
12110 const EXTRA_CRC: u8 = 46u8;
12111 const ENCODED_LEN: usize = 9usize;
12112 fn deser(
12113 _version: MavlinkVersion,
12114 __input: &[u8],
12115 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12116 let avail_len = __input.len();
12117 let mut payload_buf = [0; Self::ENCODED_LEN];
12118 let mut buf = if avail_len < Self::ENCODED_LEN {
12119 payload_buf[0..avail_len].copy_from_slice(__input);
12120 Bytes::new(&payload_buf)
12121 } else {
12122 Bytes::new(__input)
12123 };
12124 let mut __struct = Self::default();
12125 __struct.time_boot_ms = buf.get_u32_le()?;
12126 __struct.value = buf.get_f32_le()?;
12127 __struct.ind = buf.get_u8()?;
12128 Ok(__struct)
12129 }
12130 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12131 let mut __tmp = BytesMut::new(bytes);
12132 #[allow(clippy::absurd_extreme_comparisons)]
12133 #[allow(unused_comparisons)]
12134 if __tmp.remaining() < Self::ENCODED_LEN {
12135 panic!(
12136 "buffer is too small (need {} bytes, but got {})",
12137 Self::ENCODED_LEN,
12138 __tmp.remaining(),
12139 )
12140 }
12141 __tmp.put_u32_le(self.time_boot_ms);
12142 __tmp.put_f32_le(self.value);
12143 __tmp.put_u8(self.ind);
12144 if matches!(version, MavlinkVersion::V2) {
12145 let len = __tmp.len();
12146 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12147 } else {
12148 __tmp.len()
12149 }
12150 }
12151}
12152#[doc = "Large debug/prototyping array. The message uses the maximum available payload for data. The array_id and name fields are used to discriminate between messages in code and in user interfaces (respectively). Do not use in production code."]
12153#[doc = ""]
12154#[doc = "ID: 350"]
12155#[derive(Debug, Clone, PartialEq)]
12156#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12157#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12158#[cfg_attr(feature = "ts", derive(TS))]
12159#[cfg_attr(feature = "ts", ts(export))]
12160pub struct DEBUG_FLOAT_ARRAY_DATA {
12161 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
12162 pub time_usec: u64,
12163 #[doc = "Unique ID used to discriminate between arrays"]
12164 pub array_id: u16,
12165 #[doc = "Name, for human-friendly display in a Ground Control Station"]
12166 #[cfg_attr(feature = "ts", ts(type = "string"))]
12167 pub name: CharArray<10>,
12168 #[doc = "data"]
12169 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
12170 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12171 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
12172 pub data: [f32; 58],
12173}
12174impl DEBUG_FLOAT_ARRAY_DATA {
12175 pub const ENCODED_LEN: usize = 252usize;
12176 pub const DEFAULT: Self = Self {
12177 time_usec: 0_u64,
12178 array_id: 0_u16,
12179 name: CharArray::new([0_u8; 10usize]),
12180 data: [0.0_f32; 58usize],
12181 };
12182 #[cfg(feature = "arbitrary")]
12183 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12184 use arbitrary::{Arbitrary, Unstructured};
12185 let mut buf = [0u8; 1024];
12186 rng.fill_bytes(&mut buf);
12187 let mut unstructured = Unstructured::new(&buf);
12188 Self::arbitrary(&mut unstructured).unwrap_or_default()
12189 }
12190}
12191impl Default for DEBUG_FLOAT_ARRAY_DATA {
12192 fn default() -> Self {
12193 Self::DEFAULT.clone()
12194 }
12195}
12196impl MessageData for DEBUG_FLOAT_ARRAY_DATA {
12197 type Message = MavMessage;
12198 const ID: u32 = 350u32;
12199 const NAME: &'static str = "DEBUG_FLOAT_ARRAY";
12200 const EXTRA_CRC: u8 = 232u8;
12201 const ENCODED_LEN: usize = 252usize;
12202 fn deser(
12203 _version: MavlinkVersion,
12204 __input: &[u8],
12205 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12206 let avail_len = __input.len();
12207 let mut payload_buf = [0; Self::ENCODED_LEN];
12208 let mut buf = if avail_len < Self::ENCODED_LEN {
12209 payload_buf[0..avail_len].copy_from_slice(__input);
12210 Bytes::new(&payload_buf)
12211 } else {
12212 Bytes::new(__input)
12213 };
12214 let mut __struct = Self::default();
12215 __struct.time_usec = buf.get_u64_le()?;
12216 __struct.array_id = buf.get_u16_le()?;
12217 let mut tmp = [0_u8; 10usize];
12218 for v in &mut tmp {
12219 *v = buf.get_u8()?;
12220 }
12221 __struct.name = CharArray::new(tmp);
12222 for v in &mut __struct.data {
12223 let val = buf.get_f32_le()?;
12224 *v = val;
12225 }
12226 Ok(__struct)
12227 }
12228 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12229 let mut __tmp = BytesMut::new(bytes);
12230 #[allow(clippy::absurd_extreme_comparisons)]
12231 #[allow(unused_comparisons)]
12232 if __tmp.remaining() < Self::ENCODED_LEN {
12233 panic!(
12234 "buffer is too small (need {} bytes, but got {})",
12235 Self::ENCODED_LEN,
12236 __tmp.remaining(),
12237 )
12238 }
12239 __tmp.put_u64_le(self.time_usec);
12240 __tmp.put_u16_le(self.array_id);
12241 for val in &self.name {
12242 __tmp.put_u8(*val);
12243 }
12244 if matches!(version, MavlinkVersion::V2) {
12245 for val in &self.data {
12246 __tmp.put_f32_le(*val);
12247 }
12248 let len = __tmp.len();
12249 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12250 } else {
12251 __tmp.len()
12252 }
12253 }
12254}
12255#[doc = "To debug something using a named 3D vector."]
12256#[doc = ""]
12257#[doc = "ID: 250"]
12258#[derive(Debug, Clone, PartialEq)]
12259#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12260#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12261#[cfg_attr(feature = "ts", derive(TS))]
12262#[cfg_attr(feature = "ts", ts(export))]
12263pub struct DEBUG_VECT_DATA {
12264 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
12265 pub time_usec: u64,
12266 #[doc = "x"]
12267 pub x: f32,
12268 #[doc = "y"]
12269 pub y: f32,
12270 #[doc = "z"]
12271 pub z: f32,
12272 #[doc = "Name"]
12273 #[cfg_attr(feature = "ts", ts(type = "string"))]
12274 pub name: CharArray<10>,
12275}
12276impl DEBUG_VECT_DATA {
12277 pub const ENCODED_LEN: usize = 30usize;
12278 pub const DEFAULT: Self = Self {
12279 time_usec: 0_u64,
12280 x: 0.0_f32,
12281 y: 0.0_f32,
12282 z: 0.0_f32,
12283 name: CharArray::new([0_u8; 10usize]),
12284 };
12285 #[cfg(feature = "arbitrary")]
12286 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12287 use arbitrary::{Arbitrary, Unstructured};
12288 let mut buf = [0u8; 1024];
12289 rng.fill_bytes(&mut buf);
12290 let mut unstructured = Unstructured::new(&buf);
12291 Self::arbitrary(&mut unstructured).unwrap_or_default()
12292 }
12293}
12294impl Default for DEBUG_VECT_DATA {
12295 fn default() -> Self {
12296 Self::DEFAULT.clone()
12297 }
12298}
12299impl MessageData for DEBUG_VECT_DATA {
12300 type Message = MavMessage;
12301 const ID: u32 = 250u32;
12302 const NAME: &'static str = "DEBUG_VECT";
12303 const EXTRA_CRC: u8 = 49u8;
12304 const ENCODED_LEN: usize = 30usize;
12305 fn deser(
12306 _version: MavlinkVersion,
12307 __input: &[u8],
12308 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12309 let avail_len = __input.len();
12310 let mut payload_buf = [0; Self::ENCODED_LEN];
12311 let mut buf = if avail_len < Self::ENCODED_LEN {
12312 payload_buf[0..avail_len].copy_from_slice(__input);
12313 Bytes::new(&payload_buf)
12314 } else {
12315 Bytes::new(__input)
12316 };
12317 let mut __struct = Self::default();
12318 __struct.time_usec = buf.get_u64_le()?;
12319 __struct.x = buf.get_f32_le()?;
12320 __struct.y = buf.get_f32_le()?;
12321 __struct.z = buf.get_f32_le()?;
12322 let mut tmp = [0_u8; 10usize];
12323 for v in &mut tmp {
12324 *v = buf.get_u8()?;
12325 }
12326 __struct.name = CharArray::new(tmp);
12327 Ok(__struct)
12328 }
12329 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12330 let mut __tmp = BytesMut::new(bytes);
12331 #[allow(clippy::absurd_extreme_comparisons)]
12332 #[allow(unused_comparisons)]
12333 if __tmp.remaining() < Self::ENCODED_LEN {
12334 panic!(
12335 "buffer is too small (need {} bytes, but got {})",
12336 Self::ENCODED_LEN,
12337 __tmp.remaining(),
12338 )
12339 }
12340 __tmp.put_u64_le(self.time_usec);
12341 __tmp.put_f32_le(self.x);
12342 __tmp.put_f32_le(self.y);
12343 __tmp.put_f32_le(self.z);
12344 for val in &self.name {
12345 __tmp.put_u8(*val);
12346 }
12347 if matches!(version, MavlinkVersion::V2) {
12348 let len = __tmp.len();
12349 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12350 } else {
12351 __tmp.len()
12352 }
12353 }
12354}
12355#[doc = "Distance sensor information for an onboard rangefinder."]
12356#[doc = ""]
12357#[doc = "ID: 132"]
12358#[derive(Debug, Clone, PartialEq)]
12359#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12360#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12361#[cfg_attr(feature = "ts", derive(TS))]
12362#[cfg_attr(feature = "ts", ts(export))]
12363pub struct DISTANCE_SENSOR_DATA {
12364 #[doc = "Timestamp (time since system boot)."]
12365 pub time_boot_ms: u32,
12366 #[doc = "Minimum distance the sensor can measure"]
12367 pub min_distance: u16,
12368 #[doc = "Maximum distance the sensor can measure"]
12369 pub max_distance: u16,
12370 #[doc = "Current distance reading"]
12371 pub current_distance: u16,
12372 #[doc = "Type of distance sensor."]
12373 pub mavtype: MavDistanceSensor,
12374 #[doc = "Onboard ID of the sensor"]
12375 pub id: u8,
12376 #[doc = "Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270"]
12377 pub orientation: MavSensorOrientation,
12378 #[doc = "Measurement variance. Max standard deviation is 6cm. UINT8_MAX if unknown."]
12379 pub covariance: u8,
12380 #[doc = "Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0."]
12381 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
12382 pub horizontal_fov: f32,
12383 #[doc = "Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0."]
12384 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
12385 pub vertical_fov: f32,
12386 #[doc = "Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid.\""]
12387 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
12388 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12389 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
12390 pub quaternion: [f32; 4],
12391 #[doc = "Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal."]
12392 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
12393 pub signal_quality: u8,
12394}
12395impl DISTANCE_SENSOR_DATA {
12396 pub const ENCODED_LEN: usize = 39usize;
12397 pub const DEFAULT: Self = Self {
12398 time_boot_ms: 0_u32,
12399 min_distance: 0_u16,
12400 max_distance: 0_u16,
12401 current_distance: 0_u16,
12402 mavtype: MavDistanceSensor::DEFAULT,
12403 id: 0_u8,
12404 orientation: MavSensorOrientation::DEFAULT,
12405 covariance: 0_u8,
12406 horizontal_fov: 0.0_f32,
12407 vertical_fov: 0.0_f32,
12408 quaternion: [0.0_f32; 4usize],
12409 signal_quality: 0_u8,
12410 };
12411 #[cfg(feature = "arbitrary")]
12412 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12413 use arbitrary::{Arbitrary, Unstructured};
12414 let mut buf = [0u8; 1024];
12415 rng.fill_bytes(&mut buf);
12416 let mut unstructured = Unstructured::new(&buf);
12417 Self::arbitrary(&mut unstructured).unwrap_or_default()
12418 }
12419}
12420impl Default for DISTANCE_SENSOR_DATA {
12421 fn default() -> Self {
12422 Self::DEFAULT.clone()
12423 }
12424}
12425impl MessageData for DISTANCE_SENSOR_DATA {
12426 type Message = MavMessage;
12427 const ID: u32 = 132u32;
12428 const NAME: &'static str = "DISTANCE_SENSOR";
12429 const EXTRA_CRC: u8 = 85u8;
12430 const ENCODED_LEN: usize = 39usize;
12431 fn deser(
12432 _version: MavlinkVersion,
12433 __input: &[u8],
12434 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12435 let avail_len = __input.len();
12436 let mut payload_buf = [0; Self::ENCODED_LEN];
12437 let mut buf = if avail_len < Self::ENCODED_LEN {
12438 payload_buf[0..avail_len].copy_from_slice(__input);
12439 Bytes::new(&payload_buf)
12440 } else {
12441 Bytes::new(__input)
12442 };
12443 let mut __struct = Self::default();
12444 __struct.time_boot_ms = buf.get_u32_le()?;
12445 __struct.min_distance = buf.get_u16_le()?;
12446 __struct.max_distance = buf.get_u16_le()?;
12447 __struct.current_distance = buf.get_u16_le()?;
12448 let tmp = buf.get_u8()?;
12449 __struct.mavtype =
12450 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
12451 enum_type: "MavDistanceSensor",
12452 value: tmp as u64,
12453 })?;
12454 __struct.id = buf.get_u8()?;
12455 let tmp = buf.get_u8()?;
12456 __struct.orientation =
12457 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
12458 enum_type: "MavSensorOrientation",
12459 value: tmp as u64,
12460 })?;
12461 __struct.covariance = buf.get_u8()?;
12462 __struct.horizontal_fov = buf.get_f32_le()?;
12463 __struct.vertical_fov = buf.get_f32_le()?;
12464 for v in &mut __struct.quaternion {
12465 let val = buf.get_f32_le()?;
12466 *v = val;
12467 }
12468 __struct.signal_quality = buf.get_u8()?;
12469 Ok(__struct)
12470 }
12471 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12472 let mut __tmp = BytesMut::new(bytes);
12473 #[allow(clippy::absurd_extreme_comparisons)]
12474 #[allow(unused_comparisons)]
12475 if __tmp.remaining() < Self::ENCODED_LEN {
12476 panic!(
12477 "buffer is too small (need {} bytes, but got {})",
12478 Self::ENCODED_LEN,
12479 __tmp.remaining(),
12480 )
12481 }
12482 __tmp.put_u32_le(self.time_boot_ms);
12483 __tmp.put_u16_le(self.min_distance);
12484 __tmp.put_u16_le(self.max_distance);
12485 __tmp.put_u16_le(self.current_distance);
12486 __tmp.put_u8(self.mavtype as u8);
12487 __tmp.put_u8(self.id);
12488 __tmp.put_u8(self.orientation as u8);
12489 __tmp.put_u8(self.covariance);
12490 if matches!(version, MavlinkVersion::V2) {
12491 __tmp.put_f32_le(self.horizontal_fov);
12492 __tmp.put_f32_le(self.vertical_fov);
12493 for val in &self.quaternion {
12494 __tmp.put_f32_le(*val);
12495 }
12496 __tmp.put_u8(self.signal_quality);
12497 let len = __tmp.len();
12498 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12499 } else {
12500 __tmp.len()
12501 }
12502 }
12503}
12504#[doc = "EFI status output."]
12505#[doc = ""]
12506#[doc = "ID: 225"]
12507#[derive(Debug, Clone, PartialEq)]
12508#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12509#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12510#[cfg_attr(feature = "ts", derive(TS))]
12511#[cfg_attr(feature = "ts", ts(export))]
12512pub struct EFI_STATUS_DATA {
12513 #[doc = "ECU index"]
12514 pub ecu_index: f32,
12515 #[doc = "RPM"]
12516 pub rpm: f32,
12517 #[doc = "Fuel consumed"]
12518 pub fuel_consumed: f32,
12519 #[doc = "Fuel flow rate"]
12520 pub fuel_flow: f32,
12521 #[doc = "Engine load"]
12522 pub engine_load: f32,
12523 #[doc = "Throttle position"]
12524 pub throttle_position: f32,
12525 #[doc = "Spark dwell time"]
12526 pub spark_dwell_time: f32,
12527 #[doc = "Barometric pressure"]
12528 pub barometric_pressure: f32,
12529 #[doc = "Intake manifold pressure("]
12530 pub intake_manifold_pressure: f32,
12531 #[doc = "Intake manifold temperature"]
12532 pub intake_manifold_temperature: f32,
12533 #[doc = "Cylinder head temperature"]
12534 pub cylinder_head_temperature: f32,
12535 #[doc = "Ignition timing (Crank angle degrees)"]
12536 pub ignition_timing: f32,
12537 #[doc = "Injection time"]
12538 pub injection_time: f32,
12539 #[doc = "Exhaust gas temperature"]
12540 pub exhaust_gas_temperature: f32,
12541 #[doc = "Output throttle"]
12542 pub throttle_out: f32,
12543 #[doc = "Pressure/temperature compensation"]
12544 pub pt_compensation: f32,
12545 #[doc = "EFI health status"]
12546 pub health: u8,
12547 #[doc = "Supply voltage to EFI sparking system. Zero in this value means \"unknown\", so if the supply voltage really is zero volts use 0.0001 instead."]
12548 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
12549 pub ignition_voltage: f32,
12550 #[doc = "Fuel pressure. Zero in this value means \"unknown\", so if the fuel pressure really is zero kPa use 0.0001 instead."]
12551 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
12552 pub fuel_pressure: f32,
12553}
12554impl EFI_STATUS_DATA {
12555 pub const ENCODED_LEN: usize = 73usize;
12556 pub const DEFAULT: Self = Self {
12557 ecu_index: 0.0_f32,
12558 rpm: 0.0_f32,
12559 fuel_consumed: 0.0_f32,
12560 fuel_flow: 0.0_f32,
12561 engine_load: 0.0_f32,
12562 throttle_position: 0.0_f32,
12563 spark_dwell_time: 0.0_f32,
12564 barometric_pressure: 0.0_f32,
12565 intake_manifold_pressure: 0.0_f32,
12566 intake_manifold_temperature: 0.0_f32,
12567 cylinder_head_temperature: 0.0_f32,
12568 ignition_timing: 0.0_f32,
12569 injection_time: 0.0_f32,
12570 exhaust_gas_temperature: 0.0_f32,
12571 throttle_out: 0.0_f32,
12572 pt_compensation: 0.0_f32,
12573 health: 0_u8,
12574 ignition_voltage: 0.0_f32,
12575 fuel_pressure: 0.0_f32,
12576 };
12577 #[cfg(feature = "arbitrary")]
12578 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12579 use arbitrary::{Arbitrary, Unstructured};
12580 let mut buf = [0u8; 1024];
12581 rng.fill_bytes(&mut buf);
12582 let mut unstructured = Unstructured::new(&buf);
12583 Self::arbitrary(&mut unstructured).unwrap_or_default()
12584 }
12585}
12586impl Default for EFI_STATUS_DATA {
12587 fn default() -> Self {
12588 Self::DEFAULT.clone()
12589 }
12590}
12591impl MessageData for EFI_STATUS_DATA {
12592 type Message = MavMessage;
12593 const ID: u32 = 225u32;
12594 const NAME: &'static str = "EFI_STATUS";
12595 const EXTRA_CRC: u8 = 208u8;
12596 const ENCODED_LEN: usize = 73usize;
12597 fn deser(
12598 _version: MavlinkVersion,
12599 __input: &[u8],
12600 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12601 let avail_len = __input.len();
12602 let mut payload_buf = [0; Self::ENCODED_LEN];
12603 let mut buf = if avail_len < Self::ENCODED_LEN {
12604 payload_buf[0..avail_len].copy_from_slice(__input);
12605 Bytes::new(&payload_buf)
12606 } else {
12607 Bytes::new(__input)
12608 };
12609 let mut __struct = Self::default();
12610 __struct.ecu_index = buf.get_f32_le()?;
12611 __struct.rpm = buf.get_f32_le()?;
12612 __struct.fuel_consumed = buf.get_f32_le()?;
12613 __struct.fuel_flow = buf.get_f32_le()?;
12614 __struct.engine_load = buf.get_f32_le()?;
12615 __struct.throttle_position = buf.get_f32_le()?;
12616 __struct.spark_dwell_time = buf.get_f32_le()?;
12617 __struct.barometric_pressure = buf.get_f32_le()?;
12618 __struct.intake_manifold_pressure = buf.get_f32_le()?;
12619 __struct.intake_manifold_temperature = buf.get_f32_le()?;
12620 __struct.cylinder_head_temperature = buf.get_f32_le()?;
12621 __struct.ignition_timing = buf.get_f32_le()?;
12622 __struct.injection_time = buf.get_f32_le()?;
12623 __struct.exhaust_gas_temperature = buf.get_f32_le()?;
12624 __struct.throttle_out = buf.get_f32_le()?;
12625 __struct.pt_compensation = buf.get_f32_le()?;
12626 __struct.health = buf.get_u8()?;
12627 __struct.ignition_voltage = buf.get_f32_le()?;
12628 __struct.fuel_pressure = buf.get_f32_le()?;
12629 Ok(__struct)
12630 }
12631 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12632 let mut __tmp = BytesMut::new(bytes);
12633 #[allow(clippy::absurd_extreme_comparisons)]
12634 #[allow(unused_comparisons)]
12635 if __tmp.remaining() < Self::ENCODED_LEN {
12636 panic!(
12637 "buffer is too small (need {} bytes, but got {})",
12638 Self::ENCODED_LEN,
12639 __tmp.remaining(),
12640 )
12641 }
12642 __tmp.put_f32_le(self.ecu_index);
12643 __tmp.put_f32_le(self.rpm);
12644 __tmp.put_f32_le(self.fuel_consumed);
12645 __tmp.put_f32_le(self.fuel_flow);
12646 __tmp.put_f32_le(self.engine_load);
12647 __tmp.put_f32_le(self.throttle_position);
12648 __tmp.put_f32_le(self.spark_dwell_time);
12649 __tmp.put_f32_le(self.barometric_pressure);
12650 __tmp.put_f32_le(self.intake_manifold_pressure);
12651 __tmp.put_f32_le(self.intake_manifold_temperature);
12652 __tmp.put_f32_le(self.cylinder_head_temperature);
12653 __tmp.put_f32_le(self.ignition_timing);
12654 __tmp.put_f32_le(self.injection_time);
12655 __tmp.put_f32_le(self.exhaust_gas_temperature);
12656 __tmp.put_f32_le(self.throttle_out);
12657 __tmp.put_f32_le(self.pt_compensation);
12658 __tmp.put_u8(self.health);
12659 if matches!(version, MavlinkVersion::V2) {
12660 __tmp.put_f32_le(self.ignition_voltage);
12661 __tmp.put_f32_le(self.fuel_pressure);
12662 let len = __tmp.len();
12663 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12664 } else {
12665 __tmp.len()
12666 }
12667 }
12668}
12669#[doc = "Data packet for images sent using the Image Transmission Protocol: <https://mavlink.io/en/services/image_transmission.html>."]
12670#[doc = ""]
12671#[doc = "ID: 131"]
12672#[derive(Debug, Clone, PartialEq)]
12673#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12674#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12675#[cfg_attr(feature = "ts", derive(TS))]
12676#[cfg_attr(feature = "ts", ts(export))]
12677pub struct ENCAPSULATED_DATA_DATA {
12678 #[doc = "sequence number (starting with 0 on every transmission)"]
12679 pub seqnr: u16,
12680 #[doc = "image data bytes"]
12681 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12682 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
12683 pub data: [u8; 253],
12684}
12685impl ENCAPSULATED_DATA_DATA {
12686 pub const ENCODED_LEN: usize = 255usize;
12687 pub const DEFAULT: Self = Self {
12688 seqnr: 0_u16,
12689 data: [0_u8; 253usize],
12690 };
12691 #[cfg(feature = "arbitrary")]
12692 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12693 use arbitrary::{Arbitrary, Unstructured};
12694 let mut buf = [0u8; 1024];
12695 rng.fill_bytes(&mut buf);
12696 let mut unstructured = Unstructured::new(&buf);
12697 Self::arbitrary(&mut unstructured).unwrap_or_default()
12698 }
12699}
12700impl Default for ENCAPSULATED_DATA_DATA {
12701 fn default() -> Self {
12702 Self::DEFAULT.clone()
12703 }
12704}
12705impl MessageData for ENCAPSULATED_DATA_DATA {
12706 type Message = MavMessage;
12707 const ID: u32 = 131u32;
12708 const NAME: &'static str = "ENCAPSULATED_DATA";
12709 const EXTRA_CRC: u8 = 223u8;
12710 const ENCODED_LEN: usize = 255usize;
12711 fn deser(
12712 _version: MavlinkVersion,
12713 __input: &[u8],
12714 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12715 let avail_len = __input.len();
12716 let mut payload_buf = [0; Self::ENCODED_LEN];
12717 let mut buf = if avail_len < Self::ENCODED_LEN {
12718 payload_buf[0..avail_len].copy_from_slice(__input);
12719 Bytes::new(&payload_buf)
12720 } else {
12721 Bytes::new(__input)
12722 };
12723 let mut __struct = Self::default();
12724 __struct.seqnr = buf.get_u16_le()?;
12725 for v in &mut __struct.data {
12726 let val = buf.get_u8()?;
12727 *v = val;
12728 }
12729 Ok(__struct)
12730 }
12731 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12732 let mut __tmp = BytesMut::new(bytes);
12733 #[allow(clippy::absurd_extreme_comparisons)]
12734 #[allow(unused_comparisons)]
12735 if __tmp.remaining() < Self::ENCODED_LEN {
12736 panic!(
12737 "buffer is too small (need {} bytes, but got {})",
12738 Self::ENCODED_LEN,
12739 __tmp.remaining(),
12740 )
12741 }
12742 __tmp.put_u16_le(self.seqnr);
12743 for val in &self.data {
12744 __tmp.put_u8(*val);
12745 }
12746 if matches!(version, MavlinkVersion::V2) {
12747 let len = __tmp.len();
12748 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12749 } else {
12750 __tmp.len()
12751 }
12752 }
12753}
12754#[doc = "ESC information for lower rate streaming. Recommended streaming rate 1Hz. See ESC_STATUS for higher-rate ESC data."]
12755#[doc = ""]
12756#[doc = "ID: 290"]
12757#[derive(Debug, Clone, PartialEq)]
12758#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12759#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12760#[cfg_attr(feature = "ts", derive(TS))]
12761#[cfg_attr(feature = "ts", ts(export))]
12762pub struct ESC_INFO_DATA {
12763 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number."]
12764 pub time_usec: u64,
12765 #[doc = "Number of reported errors by each ESC since boot."]
12766 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12767 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
12768 pub error_count: [u32; 4],
12769 #[doc = "Counter of data packets received."]
12770 pub counter: u16,
12771 #[doc = "Bitmap of ESC failure flags."]
12772 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12773 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
12774 pub failure_flags: [u16; 4],
12775 #[doc = "Temperature of each ESC. INT16_MAX: if data not supplied by ESC."]
12776 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12777 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
12778 pub temperature: [i16; 4],
12779 #[doc = "Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4."]
12780 pub index: u8,
12781 #[doc = "Total number of ESCs in all messages of this type. Message fields with an index higher than this should be ignored because they contain invalid data."]
12782 pub count: u8,
12783 #[doc = "Connection type protocol for all ESC."]
12784 pub connection_type: EscConnectionType,
12785 #[doc = "Information regarding online/offline status of each ESC."]
12786 pub info: u8,
12787}
12788impl ESC_INFO_DATA {
12789 pub const ENCODED_LEN: usize = 46usize;
12790 pub const DEFAULT: Self = Self {
12791 time_usec: 0_u64,
12792 error_count: [0_u32; 4usize],
12793 counter: 0_u16,
12794 failure_flags: [0_u16; 4usize],
12795 temperature: [0_i16; 4usize],
12796 index: 0_u8,
12797 count: 0_u8,
12798 connection_type: EscConnectionType::DEFAULT,
12799 info: 0_u8,
12800 };
12801 #[cfg(feature = "arbitrary")]
12802 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12803 use arbitrary::{Arbitrary, Unstructured};
12804 let mut buf = [0u8; 1024];
12805 rng.fill_bytes(&mut buf);
12806 let mut unstructured = Unstructured::new(&buf);
12807 Self::arbitrary(&mut unstructured).unwrap_or_default()
12808 }
12809}
12810impl Default for ESC_INFO_DATA {
12811 fn default() -> Self {
12812 Self::DEFAULT.clone()
12813 }
12814}
12815impl MessageData for ESC_INFO_DATA {
12816 type Message = MavMessage;
12817 const ID: u32 = 290u32;
12818 const NAME: &'static str = "ESC_INFO";
12819 const EXTRA_CRC: u8 = 251u8;
12820 const ENCODED_LEN: usize = 46usize;
12821 fn deser(
12822 _version: MavlinkVersion,
12823 __input: &[u8],
12824 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12825 let avail_len = __input.len();
12826 let mut payload_buf = [0; Self::ENCODED_LEN];
12827 let mut buf = if avail_len < Self::ENCODED_LEN {
12828 payload_buf[0..avail_len].copy_from_slice(__input);
12829 Bytes::new(&payload_buf)
12830 } else {
12831 Bytes::new(__input)
12832 };
12833 let mut __struct = Self::default();
12834 __struct.time_usec = buf.get_u64_le()?;
12835 for v in &mut __struct.error_count {
12836 let val = buf.get_u32_le()?;
12837 *v = val;
12838 }
12839 __struct.counter = buf.get_u16_le()?;
12840 for v in &mut __struct.failure_flags {
12841 let val = buf.get_u16_le()?;
12842 *v = val;
12843 }
12844 for v in &mut __struct.temperature {
12845 let val = buf.get_i16_le()?;
12846 *v = val;
12847 }
12848 __struct.index = buf.get_u8()?;
12849 __struct.count = buf.get_u8()?;
12850 let tmp = buf.get_u8()?;
12851 __struct.connection_type =
12852 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
12853 enum_type: "EscConnectionType",
12854 value: tmp as u64,
12855 })?;
12856 __struct.info = buf.get_u8()?;
12857 Ok(__struct)
12858 }
12859 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12860 let mut __tmp = BytesMut::new(bytes);
12861 #[allow(clippy::absurd_extreme_comparisons)]
12862 #[allow(unused_comparisons)]
12863 if __tmp.remaining() < Self::ENCODED_LEN {
12864 panic!(
12865 "buffer is too small (need {} bytes, but got {})",
12866 Self::ENCODED_LEN,
12867 __tmp.remaining(),
12868 )
12869 }
12870 __tmp.put_u64_le(self.time_usec);
12871 for val in &self.error_count {
12872 __tmp.put_u32_le(*val);
12873 }
12874 __tmp.put_u16_le(self.counter);
12875 for val in &self.failure_flags {
12876 __tmp.put_u16_le(*val);
12877 }
12878 for val in &self.temperature {
12879 __tmp.put_i16_le(*val);
12880 }
12881 __tmp.put_u8(self.index);
12882 __tmp.put_u8(self.count);
12883 __tmp.put_u8(self.connection_type as u8);
12884 __tmp.put_u8(self.info);
12885 if matches!(version, MavlinkVersion::V2) {
12886 let len = __tmp.len();
12887 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12888 } else {
12889 __tmp.len()
12890 }
12891 }
12892}
12893#[doc = "ESC information for higher rate streaming. Recommended streaming rate is ~10 Hz. Information that changes more slowly is sent in ESC_INFO. It should typically only be streamed on high-bandwidth links (i.e. to a companion computer)."]
12894#[doc = ""]
12895#[doc = "ID: 291"]
12896#[derive(Debug, Clone, PartialEq)]
12897#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12898#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12899#[cfg_attr(feature = "ts", derive(TS))]
12900#[cfg_attr(feature = "ts", ts(export))]
12901pub struct ESC_STATUS_DATA {
12902 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number."]
12903 pub time_usec: u64,
12904 #[doc = "Reported motor RPM from each ESC (negative for reverse rotation)."]
12905 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12906 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
12907 pub rpm: [i32; 4],
12908 #[doc = "Voltage measured from each ESC."]
12909 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12910 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
12911 pub voltage: [f32; 4],
12912 #[doc = "Current measured from each ESC."]
12913 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12914 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
12915 pub current: [f32; 4],
12916 #[doc = "Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4."]
12917 pub index: u8,
12918}
12919impl ESC_STATUS_DATA {
12920 pub const ENCODED_LEN: usize = 57usize;
12921 pub const DEFAULT: Self = Self {
12922 time_usec: 0_u64,
12923 rpm: [0_i32; 4usize],
12924 voltage: [0.0_f32; 4usize],
12925 current: [0.0_f32; 4usize],
12926 index: 0_u8,
12927 };
12928 #[cfg(feature = "arbitrary")]
12929 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12930 use arbitrary::{Arbitrary, Unstructured};
12931 let mut buf = [0u8; 1024];
12932 rng.fill_bytes(&mut buf);
12933 let mut unstructured = Unstructured::new(&buf);
12934 Self::arbitrary(&mut unstructured).unwrap_or_default()
12935 }
12936}
12937impl Default for ESC_STATUS_DATA {
12938 fn default() -> Self {
12939 Self::DEFAULT.clone()
12940 }
12941}
12942impl MessageData for ESC_STATUS_DATA {
12943 type Message = MavMessage;
12944 const ID: u32 = 291u32;
12945 const NAME: &'static str = "ESC_STATUS";
12946 const EXTRA_CRC: u8 = 10u8;
12947 const ENCODED_LEN: usize = 57usize;
12948 fn deser(
12949 _version: MavlinkVersion,
12950 __input: &[u8],
12951 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12952 let avail_len = __input.len();
12953 let mut payload_buf = [0; Self::ENCODED_LEN];
12954 let mut buf = if avail_len < Self::ENCODED_LEN {
12955 payload_buf[0..avail_len].copy_from_slice(__input);
12956 Bytes::new(&payload_buf)
12957 } else {
12958 Bytes::new(__input)
12959 };
12960 let mut __struct = Self::default();
12961 __struct.time_usec = buf.get_u64_le()?;
12962 for v in &mut __struct.rpm {
12963 let val = buf.get_i32_le()?;
12964 *v = val;
12965 }
12966 for v in &mut __struct.voltage {
12967 let val = buf.get_f32_le()?;
12968 *v = val;
12969 }
12970 for v in &mut __struct.current {
12971 let val = buf.get_f32_le()?;
12972 *v = val;
12973 }
12974 __struct.index = buf.get_u8()?;
12975 Ok(__struct)
12976 }
12977 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12978 let mut __tmp = BytesMut::new(bytes);
12979 #[allow(clippy::absurd_extreme_comparisons)]
12980 #[allow(unused_comparisons)]
12981 if __tmp.remaining() < Self::ENCODED_LEN {
12982 panic!(
12983 "buffer is too small (need {} bytes, but got {})",
12984 Self::ENCODED_LEN,
12985 __tmp.remaining(),
12986 )
12987 }
12988 __tmp.put_u64_le(self.time_usec);
12989 for val in &self.rpm {
12990 __tmp.put_i32_le(*val);
12991 }
12992 for val in &self.voltage {
12993 __tmp.put_f32_le(*val);
12994 }
12995 for val in &self.current {
12996 __tmp.put_f32_le(*val);
12997 }
12998 __tmp.put_u8(self.index);
12999 if matches!(version, MavlinkVersion::V2) {
13000 let len = __tmp.len();
13001 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13002 } else {
13003 __tmp.len()
13004 }
13005 }
13006}
13007#[doc = "Estimator status message including flags, innovation test ratios and estimated accuracies. The flags message is an integer bitmask containing information on which EKF outputs are valid. See the ESTIMATOR_STATUS_FLAGS enum definition for further information. The innovation test ratios show the magnitude of the sensor innovation divided by the innovation check threshold. Under normal operation the innovation test ratios should be below 0.5 with occasional values up to 1.0. Values greater than 1.0 should be rare under normal operation and indicate that a measurement has been rejected by the filter. The user should be notified if an innovation test ratio greater than 1.0 is recorded. Notifications for values in the range between 0.5 and 1.0 should be optional and controllable by the user."]
13008#[doc = ""]
13009#[doc = "ID: 230"]
13010#[derive(Debug, Clone, PartialEq)]
13011#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13012#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13013#[cfg_attr(feature = "ts", derive(TS))]
13014#[cfg_attr(feature = "ts", ts(export))]
13015pub struct ESTIMATOR_STATUS_DATA {
13016 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
13017 pub time_usec: u64,
13018 #[doc = "Velocity innovation test ratio"]
13019 pub vel_ratio: f32,
13020 #[doc = "Horizontal position innovation test ratio"]
13021 pub pos_horiz_ratio: f32,
13022 #[doc = "Vertical position innovation test ratio"]
13023 pub pos_vert_ratio: f32,
13024 #[doc = "Magnetometer innovation test ratio"]
13025 pub mag_ratio: f32,
13026 #[doc = "Height above terrain innovation test ratio"]
13027 pub hagl_ratio: f32,
13028 #[doc = "True airspeed innovation test ratio"]
13029 pub tas_ratio: f32,
13030 #[doc = "Horizontal position 1-STD accuracy relative to the EKF local origin"]
13031 pub pos_horiz_accuracy: f32,
13032 #[doc = "Vertical position 1-STD accuracy relative to the EKF local origin"]
13033 pub pos_vert_accuracy: f32,
13034 #[doc = "Bitmap indicating which EKF outputs are valid."]
13035 pub flags: EstimatorStatusFlags,
13036}
13037impl ESTIMATOR_STATUS_DATA {
13038 pub const ENCODED_LEN: usize = 42usize;
13039 pub const DEFAULT: Self = Self {
13040 time_usec: 0_u64,
13041 vel_ratio: 0.0_f32,
13042 pos_horiz_ratio: 0.0_f32,
13043 pos_vert_ratio: 0.0_f32,
13044 mag_ratio: 0.0_f32,
13045 hagl_ratio: 0.0_f32,
13046 tas_ratio: 0.0_f32,
13047 pos_horiz_accuracy: 0.0_f32,
13048 pos_vert_accuracy: 0.0_f32,
13049 flags: EstimatorStatusFlags::DEFAULT,
13050 };
13051 #[cfg(feature = "arbitrary")]
13052 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13053 use arbitrary::{Arbitrary, Unstructured};
13054 let mut buf = [0u8; 1024];
13055 rng.fill_bytes(&mut buf);
13056 let mut unstructured = Unstructured::new(&buf);
13057 Self::arbitrary(&mut unstructured).unwrap_or_default()
13058 }
13059}
13060impl Default for ESTIMATOR_STATUS_DATA {
13061 fn default() -> Self {
13062 Self::DEFAULT.clone()
13063 }
13064}
13065impl MessageData for ESTIMATOR_STATUS_DATA {
13066 type Message = MavMessage;
13067 const ID: u32 = 230u32;
13068 const NAME: &'static str = "ESTIMATOR_STATUS";
13069 const EXTRA_CRC: u8 = 163u8;
13070 const ENCODED_LEN: usize = 42usize;
13071 fn deser(
13072 _version: MavlinkVersion,
13073 __input: &[u8],
13074 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13075 let avail_len = __input.len();
13076 let mut payload_buf = [0; Self::ENCODED_LEN];
13077 let mut buf = if avail_len < Self::ENCODED_LEN {
13078 payload_buf[0..avail_len].copy_from_slice(__input);
13079 Bytes::new(&payload_buf)
13080 } else {
13081 Bytes::new(__input)
13082 };
13083 let mut __struct = Self::default();
13084 __struct.time_usec = buf.get_u64_le()?;
13085 __struct.vel_ratio = buf.get_f32_le()?;
13086 __struct.pos_horiz_ratio = buf.get_f32_le()?;
13087 __struct.pos_vert_ratio = buf.get_f32_le()?;
13088 __struct.mag_ratio = buf.get_f32_le()?;
13089 __struct.hagl_ratio = buf.get_f32_le()?;
13090 __struct.tas_ratio = buf.get_f32_le()?;
13091 __struct.pos_horiz_accuracy = buf.get_f32_le()?;
13092 __struct.pos_vert_accuracy = buf.get_f32_le()?;
13093 let tmp = buf.get_u16_le()?;
13094 __struct.flags = EstimatorStatusFlags::from_bits(
13095 tmp as <EstimatorStatusFlags as Flags>::Bits,
13096 )
13097 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
13098 flag_type: "EstimatorStatusFlags",
13099 value: tmp as u64,
13100 })?;
13101 Ok(__struct)
13102 }
13103 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13104 let mut __tmp = BytesMut::new(bytes);
13105 #[allow(clippy::absurd_extreme_comparisons)]
13106 #[allow(unused_comparisons)]
13107 if __tmp.remaining() < Self::ENCODED_LEN {
13108 panic!(
13109 "buffer is too small (need {} bytes, but got {})",
13110 Self::ENCODED_LEN,
13111 __tmp.remaining(),
13112 )
13113 }
13114 __tmp.put_u64_le(self.time_usec);
13115 __tmp.put_f32_le(self.vel_ratio);
13116 __tmp.put_f32_le(self.pos_horiz_ratio);
13117 __tmp.put_f32_le(self.pos_vert_ratio);
13118 __tmp.put_f32_le(self.mag_ratio);
13119 __tmp.put_f32_le(self.hagl_ratio);
13120 __tmp.put_f32_le(self.tas_ratio);
13121 __tmp.put_f32_le(self.pos_horiz_accuracy);
13122 __tmp.put_f32_le(self.pos_vert_accuracy);
13123 __tmp.put_u16_le(self.flags.bits() as u16);
13124 if matches!(version, MavlinkVersion::V2) {
13125 let len = __tmp.len();
13126 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13127 } else {
13128 __tmp.len()
13129 }
13130 }
13131}
13132#[doc = "Event message. Each new event from a particular component gets a new sequence number. The same message might be sent multiple times if (re-)requested. Most events are broadcast, some can be specific to a target component (as receivers keep track of the sequence for missed events, all events need to be broadcast. Thus we use destination_component instead of target_component)."]
13133#[doc = ""]
13134#[doc = "ID: 410"]
13135#[derive(Debug, Clone, PartialEq)]
13136#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13137#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13138#[cfg_attr(feature = "ts", derive(TS))]
13139#[cfg_attr(feature = "ts", ts(export))]
13140pub struct EVENT_DATA {
13141 #[doc = "Event ID (as defined in the component metadata)"]
13142 pub id: u32,
13143 #[doc = "Timestamp (time since system boot when the event happened)."]
13144 pub event_time_boot_ms: u32,
13145 #[doc = "Sequence number."]
13146 pub sequence: u16,
13147 #[doc = "Component ID"]
13148 pub destination_component: u8,
13149 #[doc = "System ID"]
13150 pub destination_system: u8,
13151 #[doc = "Log levels: 4 bits MSB: internal (for logging purposes), 4 bits LSB: external. Levels: Emergency = 0, Alert = 1, Critical = 2, Error = 3, Warning = 4, Notice = 5, Info = 6, Debug = 7, Protocol = 8, Disabled = 9"]
13152 pub log_levels: u8,
13153 #[doc = "Arguments (depend on event ID)."]
13154 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13155 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
13156 pub arguments: [u8; 40],
13157}
13158impl EVENT_DATA {
13159 pub const ENCODED_LEN: usize = 53usize;
13160 pub const DEFAULT: Self = Self {
13161 id: 0_u32,
13162 event_time_boot_ms: 0_u32,
13163 sequence: 0_u16,
13164 destination_component: 0_u8,
13165 destination_system: 0_u8,
13166 log_levels: 0_u8,
13167 arguments: [0_u8; 40usize],
13168 };
13169 #[cfg(feature = "arbitrary")]
13170 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13171 use arbitrary::{Arbitrary, Unstructured};
13172 let mut buf = [0u8; 1024];
13173 rng.fill_bytes(&mut buf);
13174 let mut unstructured = Unstructured::new(&buf);
13175 Self::arbitrary(&mut unstructured).unwrap_or_default()
13176 }
13177}
13178impl Default for EVENT_DATA {
13179 fn default() -> Self {
13180 Self::DEFAULT.clone()
13181 }
13182}
13183impl MessageData for EVENT_DATA {
13184 type Message = MavMessage;
13185 const ID: u32 = 410u32;
13186 const NAME: &'static str = "EVENT";
13187 const EXTRA_CRC: u8 = 160u8;
13188 const ENCODED_LEN: usize = 53usize;
13189 fn deser(
13190 _version: MavlinkVersion,
13191 __input: &[u8],
13192 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13193 let avail_len = __input.len();
13194 let mut payload_buf = [0; Self::ENCODED_LEN];
13195 let mut buf = if avail_len < Self::ENCODED_LEN {
13196 payload_buf[0..avail_len].copy_from_slice(__input);
13197 Bytes::new(&payload_buf)
13198 } else {
13199 Bytes::new(__input)
13200 };
13201 let mut __struct = Self::default();
13202 __struct.id = buf.get_u32_le()?;
13203 __struct.event_time_boot_ms = buf.get_u32_le()?;
13204 __struct.sequence = buf.get_u16_le()?;
13205 __struct.destination_component = buf.get_u8()?;
13206 __struct.destination_system = buf.get_u8()?;
13207 __struct.log_levels = buf.get_u8()?;
13208 for v in &mut __struct.arguments {
13209 let val = buf.get_u8()?;
13210 *v = val;
13211 }
13212 Ok(__struct)
13213 }
13214 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13215 let mut __tmp = BytesMut::new(bytes);
13216 #[allow(clippy::absurd_extreme_comparisons)]
13217 #[allow(unused_comparisons)]
13218 if __tmp.remaining() < Self::ENCODED_LEN {
13219 panic!(
13220 "buffer is too small (need {} bytes, but got {})",
13221 Self::ENCODED_LEN,
13222 __tmp.remaining(),
13223 )
13224 }
13225 __tmp.put_u32_le(self.id);
13226 __tmp.put_u32_le(self.event_time_boot_ms);
13227 __tmp.put_u16_le(self.sequence);
13228 __tmp.put_u8(self.destination_component);
13229 __tmp.put_u8(self.destination_system);
13230 __tmp.put_u8(self.log_levels);
13231 for val in &self.arguments {
13232 __tmp.put_u8(*val);
13233 }
13234 if matches!(version, MavlinkVersion::V2) {
13235 let len = __tmp.len();
13236 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13237 } else {
13238 __tmp.len()
13239 }
13240 }
13241}
13242#[doc = "Provides state for additional features."]
13243#[doc = ""]
13244#[doc = "ID: 245"]
13245#[derive(Debug, Clone, PartialEq)]
13246#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13247#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13248#[cfg_attr(feature = "ts", derive(TS))]
13249#[cfg_attr(feature = "ts", ts(export))]
13250pub struct EXTENDED_SYS_STATE_DATA {
13251 #[doc = "The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration."]
13252 pub vtol_state: MavVtolState,
13253 #[doc = "The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown."]
13254 pub landed_state: MavLandedState,
13255}
13256impl EXTENDED_SYS_STATE_DATA {
13257 pub const ENCODED_LEN: usize = 2usize;
13258 pub const DEFAULT: Self = Self {
13259 vtol_state: MavVtolState::DEFAULT,
13260 landed_state: MavLandedState::DEFAULT,
13261 };
13262 #[cfg(feature = "arbitrary")]
13263 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13264 use arbitrary::{Arbitrary, Unstructured};
13265 let mut buf = [0u8; 1024];
13266 rng.fill_bytes(&mut buf);
13267 let mut unstructured = Unstructured::new(&buf);
13268 Self::arbitrary(&mut unstructured).unwrap_or_default()
13269 }
13270}
13271impl Default for EXTENDED_SYS_STATE_DATA {
13272 fn default() -> Self {
13273 Self::DEFAULT.clone()
13274 }
13275}
13276impl MessageData for EXTENDED_SYS_STATE_DATA {
13277 type Message = MavMessage;
13278 const ID: u32 = 245u32;
13279 const NAME: &'static str = "EXTENDED_SYS_STATE";
13280 const EXTRA_CRC: u8 = 130u8;
13281 const ENCODED_LEN: usize = 2usize;
13282 fn deser(
13283 _version: MavlinkVersion,
13284 __input: &[u8],
13285 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13286 let avail_len = __input.len();
13287 let mut payload_buf = [0; Self::ENCODED_LEN];
13288 let mut buf = if avail_len < Self::ENCODED_LEN {
13289 payload_buf[0..avail_len].copy_from_slice(__input);
13290 Bytes::new(&payload_buf)
13291 } else {
13292 Bytes::new(__input)
13293 };
13294 let mut __struct = Self::default();
13295 let tmp = buf.get_u8()?;
13296 __struct.vtol_state =
13297 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
13298 enum_type: "MavVtolState",
13299 value: tmp as u64,
13300 })?;
13301 let tmp = buf.get_u8()?;
13302 __struct.landed_state =
13303 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
13304 enum_type: "MavLandedState",
13305 value: tmp as u64,
13306 })?;
13307 Ok(__struct)
13308 }
13309 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13310 let mut __tmp = BytesMut::new(bytes);
13311 #[allow(clippy::absurd_extreme_comparisons)]
13312 #[allow(unused_comparisons)]
13313 if __tmp.remaining() < Self::ENCODED_LEN {
13314 panic!(
13315 "buffer is too small (need {} bytes, but got {})",
13316 Self::ENCODED_LEN,
13317 __tmp.remaining(),
13318 )
13319 }
13320 __tmp.put_u8(self.vtol_state as u8);
13321 __tmp.put_u8(self.landed_state as u8);
13322 if matches!(version, MavlinkVersion::V2) {
13323 let len = __tmp.len();
13324 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13325 } else {
13326 __tmp.len()
13327 }
13328 }
13329}
13330#[doc = "Status of geo-fencing. Sent in extended status stream when fencing enabled."]
13331#[doc = ""]
13332#[doc = "ID: 162"]
13333#[derive(Debug, Clone, PartialEq)]
13334#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13335#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13336#[cfg_attr(feature = "ts", derive(TS))]
13337#[cfg_attr(feature = "ts", ts(export))]
13338pub struct FENCE_STATUS_DATA {
13339 #[doc = "Time (since boot) of last breach."]
13340 pub breach_time: u32,
13341 #[doc = "Number of fence breaches."]
13342 pub breach_count: u16,
13343 #[doc = "Breach status (0 if currently inside fence, 1 if outside)."]
13344 pub breach_status: u8,
13345 #[doc = "Last breach type."]
13346 pub breach_type: FenceBreach,
13347 #[doc = "Active action to prevent fence breach"]
13348 #[cfg_attr(feature = "serde", serde(default))]
13349 pub breach_mitigation: FenceMitigate,
13350}
13351impl FENCE_STATUS_DATA {
13352 pub const ENCODED_LEN: usize = 9usize;
13353 pub const DEFAULT: Self = Self {
13354 breach_time: 0_u32,
13355 breach_count: 0_u16,
13356 breach_status: 0_u8,
13357 breach_type: FenceBreach::DEFAULT,
13358 breach_mitigation: FenceMitigate::DEFAULT,
13359 };
13360 #[cfg(feature = "arbitrary")]
13361 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13362 use arbitrary::{Arbitrary, Unstructured};
13363 let mut buf = [0u8; 1024];
13364 rng.fill_bytes(&mut buf);
13365 let mut unstructured = Unstructured::new(&buf);
13366 Self::arbitrary(&mut unstructured).unwrap_or_default()
13367 }
13368}
13369impl Default for FENCE_STATUS_DATA {
13370 fn default() -> Self {
13371 Self::DEFAULT.clone()
13372 }
13373}
13374impl MessageData for FENCE_STATUS_DATA {
13375 type Message = MavMessage;
13376 const ID: u32 = 162u32;
13377 const NAME: &'static str = "FENCE_STATUS";
13378 const EXTRA_CRC: u8 = 189u8;
13379 const ENCODED_LEN: usize = 9usize;
13380 fn deser(
13381 _version: MavlinkVersion,
13382 __input: &[u8],
13383 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13384 let avail_len = __input.len();
13385 let mut payload_buf = [0; Self::ENCODED_LEN];
13386 let mut buf = if avail_len < Self::ENCODED_LEN {
13387 payload_buf[0..avail_len].copy_from_slice(__input);
13388 Bytes::new(&payload_buf)
13389 } else {
13390 Bytes::new(__input)
13391 };
13392 let mut __struct = Self::default();
13393 __struct.breach_time = buf.get_u32_le()?;
13394 __struct.breach_count = buf.get_u16_le()?;
13395 __struct.breach_status = buf.get_u8()?;
13396 let tmp = buf.get_u8()?;
13397 __struct.breach_type =
13398 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
13399 enum_type: "FenceBreach",
13400 value: tmp as u64,
13401 })?;
13402 let tmp = buf.get_u8()?;
13403 __struct.breach_mitigation =
13404 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
13405 enum_type: "FenceMitigate",
13406 value: tmp as u64,
13407 })?;
13408 Ok(__struct)
13409 }
13410 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13411 let mut __tmp = BytesMut::new(bytes);
13412 #[allow(clippy::absurd_extreme_comparisons)]
13413 #[allow(unused_comparisons)]
13414 if __tmp.remaining() < Self::ENCODED_LEN {
13415 panic!(
13416 "buffer is too small (need {} bytes, but got {})",
13417 Self::ENCODED_LEN,
13418 __tmp.remaining(),
13419 )
13420 }
13421 __tmp.put_u32_le(self.breach_time);
13422 __tmp.put_u16_le(self.breach_count);
13423 __tmp.put_u8(self.breach_status);
13424 __tmp.put_u8(self.breach_type as u8);
13425 if matches!(version, MavlinkVersion::V2) {
13426 __tmp.put_u8(self.breach_mitigation as u8);
13427 let len = __tmp.len();
13428 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13429 } else {
13430 __tmp.len()
13431 }
13432 }
13433}
13434#[doc = "File transfer protocol message: <https://mavlink.io/en/services/ftp.html>."]
13435#[doc = ""]
13436#[doc = "ID: 110"]
13437#[derive(Debug, Clone, PartialEq)]
13438#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13439#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13440#[cfg_attr(feature = "ts", derive(TS))]
13441#[cfg_attr(feature = "ts", ts(export))]
13442pub struct FILE_TRANSFER_PROTOCOL_DATA {
13443 #[doc = "Network ID (0 for broadcast)"]
13444 pub target_network: u8,
13445 #[doc = "System ID (0 for broadcast)"]
13446 pub target_system: u8,
13447 #[doc = "Component ID (0 for broadcast)"]
13448 pub target_component: u8,
13449 #[doc = "Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The content/format of this block is defined in <https://mavlink.io/en/services/ftp.html>."]
13450 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13451 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
13452 pub payload: [u8; 251],
13453}
13454impl FILE_TRANSFER_PROTOCOL_DATA {
13455 pub const ENCODED_LEN: usize = 254usize;
13456 pub const DEFAULT: Self = Self {
13457 target_network: 0_u8,
13458 target_system: 0_u8,
13459 target_component: 0_u8,
13460 payload: [0_u8; 251usize],
13461 };
13462 #[cfg(feature = "arbitrary")]
13463 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13464 use arbitrary::{Arbitrary, Unstructured};
13465 let mut buf = [0u8; 1024];
13466 rng.fill_bytes(&mut buf);
13467 let mut unstructured = Unstructured::new(&buf);
13468 Self::arbitrary(&mut unstructured).unwrap_or_default()
13469 }
13470}
13471impl Default for FILE_TRANSFER_PROTOCOL_DATA {
13472 fn default() -> Self {
13473 Self::DEFAULT.clone()
13474 }
13475}
13476impl MessageData for FILE_TRANSFER_PROTOCOL_DATA {
13477 type Message = MavMessage;
13478 const ID: u32 = 110u32;
13479 const NAME: &'static str = "FILE_TRANSFER_PROTOCOL";
13480 const EXTRA_CRC: u8 = 84u8;
13481 const ENCODED_LEN: usize = 254usize;
13482 fn deser(
13483 _version: MavlinkVersion,
13484 __input: &[u8],
13485 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13486 let avail_len = __input.len();
13487 let mut payload_buf = [0; Self::ENCODED_LEN];
13488 let mut buf = if avail_len < Self::ENCODED_LEN {
13489 payload_buf[0..avail_len].copy_from_slice(__input);
13490 Bytes::new(&payload_buf)
13491 } else {
13492 Bytes::new(__input)
13493 };
13494 let mut __struct = Self::default();
13495 __struct.target_network = buf.get_u8()?;
13496 __struct.target_system = buf.get_u8()?;
13497 __struct.target_component = buf.get_u8()?;
13498 for v in &mut __struct.payload {
13499 let val = buf.get_u8()?;
13500 *v = val;
13501 }
13502 Ok(__struct)
13503 }
13504 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13505 let mut __tmp = BytesMut::new(bytes);
13506 #[allow(clippy::absurd_extreme_comparisons)]
13507 #[allow(unused_comparisons)]
13508 if __tmp.remaining() < Self::ENCODED_LEN {
13509 panic!(
13510 "buffer is too small (need {} bytes, but got {})",
13511 Self::ENCODED_LEN,
13512 __tmp.remaining(),
13513 )
13514 }
13515 __tmp.put_u8(self.target_network);
13516 __tmp.put_u8(self.target_system);
13517 __tmp.put_u8(self.target_component);
13518 for val in &self.payload {
13519 __tmp.put_u8(*val);
13520 }
13521 if matches!(version, MavlinkVersion::V2) {
13522 let len = __tmp.len();
13523 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13524 } else {
13525 __tmp.len()
13526 }
13527 }
13528}
13529#[doc = "Flight information. This includes time since boot for arm, takeoff, and land, and a flight number. Takeoff and landing values reset to zero on arm. This can be requested using MAV_CMD_REQUEST_MESSAGE. Note, some fields are misnamed - timestamps are from boot (not UTC) and the flight_uuid is a sequence number."]
13530#[doc = ""]
13531#[doc = "ID: 264"]
13532#[derive(Debug, Clone, PartialEq)]
13533#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13534#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13535#[cfg_attr(feature = "ts", derive(TS))]
13536#[cfg_attr(feature = "ts", ts(export))]
13537pub struct FLIGHT_INFORMATION_DATA {
13538 #[doc = "Timestamp at arming (since system boot). Set to 0 on boot. Set value on arming. Note, field is misnamed UTC."]
13539 pub arming_time_utc: u64,
13540 #[doc = "Timestamp at takeoff (since system boot). Set to 0 at boot and on arming. Note, field is misnamed UTC."]
13541 pub takeoff_time_utc: u64,
13542 #[doc = "Flight number. Note, field is misnamed UUID."]
13543 pub flight_uuid: u64,
13544 #[doc = "Timestamp (time since system boot)."]
13545 pub time_boot_ms: u32,
13546 #[doc = "Timestamp at landing (in ms since system boot). Set to 0 at boot and on arming."]
13547 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13548 pub landing_time: u32,
13549}
13550impl FLIGHT_INFORMATION_DATA {
13551 pub const ENCODED_LEN: usize = 32usize;
13552 pub const DEFAULT: Self = Self {
13553 arming_time_utc: 0_u64,
13554 takeoff_time_utc: 0_u64,
13555 flight_uuid: 0_u64,
13556 time_boot_ms: 0_u32,
13557 landing_time: 0_u32,
13558 };
13559 #[cfg(feature = "arbitrary")]
13560 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13561 use arbitrary::{Arbitrary, Unstructured};
13562 let mut buf = [0u8; 1024];
13563 rng.fill_bytes(&mut buf);
13564 let mut unstructured = Unstructured::new(&buf);
13565 Self::arbitrary(&mut unstructured).unwrap_or_default()
13566 }
13567}
13568impl Default for FLIGHT_INFORMATION_DATA {
13569 fn default() -> Self {
13570 Self::DEFAULT.clone()
13571 }
13572}
13573impl MessageData for FLIGHT_INFORMATION_DATA {
13574 type Message = MavMessage;
13575 const ID: u32 = 264u32;
13576 const NAME: &'static str = "FLIGHT_INFORMATION";
13577 const EXTRA_CRC: u8 = 49u8;
13578 const ENCODED_LEN: usize = 32usize;
13579 fn deser(
13580 _version: MavlinkVersion,
13581 __input: &[u8],
13582 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13583 let avail_len = __input.len();
13584 let mut payload_buf = [0; Self::ENCODED_LEN];
13585 let mut buf = if avail_len < Self::ENCODED_LEN {
13586 payload_buf[0..avail_len].copy_from_slice(__input);
13587 Bytes::new(&payload_buf)
13588 } else {
13589 Bytes::new(__input)
13590 };
13591 let mut __struct = Self::default();
13592 __struct.arming_time_utc = buf.get_u64_le()?;
13593 __struct.takeoff_time_utc = buf.get_u64_le()?;
13594 __struct.flight_uuid = buf.get_u64_le()?;
13595 __struct.time_boot_ms = buf.get_u32_le()?;
13596 __struct.landing_time = buf.get_u32_le()?;
13597 Ok(__struct)
13598 }
13599 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13600 let mut __tmp = BytesMut::new(bytes);
13601 #[allow(clippy::absurd_extreme_comparisons)]
13602 #[allow(unused_comparisons)]
13603 if __tmp.remaining() < Self::ENCODED_LEN {
13604 panic!(
13605 "buffer is too small (need {} bytes, but got {})",
13606 Self::ENCODED_LEN,
13607 __tmp.remaining(),
13608 )
13609 }
13610 __tmp.put_u64_le(self.arming_time_utc);
13611 __tmp.put_u64_le(self.takeoff_time_utc);
13612 __tmp.put_u64_le(self.flight_uuid);
13613 __tmp.put_u32_le(self.time_boot_ms);
13614 if matches!(version, MavlinkVersion::V2) {
13615 __tmp.put_u32_le(self.landing_time);
13616 let len = __tmp.len();
13617 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13618 } else {
13619 __tmp.len()
13620 }
13621 }
13622}
13623#[doc = "Current motion information from a designated system."]
13624#[doc = ""]
13625#[doc = "ID: 144"]
13626#[derive(Debug, Clone, PartialEq)]
13627#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13628#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13629#[cfg_attr(feature = "ts", derive(TS))]
13630#[cfg_attr(feature = "ts", ts(export))]
13631pub struct FOLLOW_TARGET_DATA {
13632 #[doc = "Timestamp (time since system boot)."]
13633 pub timestamp: u64,
13634 #[doc = "button states or switches of a tracker device"]
13635 pub custom_state: u64,
13636 #[doc = "Latitude (WGS84)"]
13637 pub lat: i32,
13638 #[doc = "Longitude (WGS84)"]
13639 pub lon: i32,
13640 #[doc = "Altitude (MSL)"]
13641 pub alt: f32,
13642 #[doc = "target velocity (0,0,0) for unknown"]
13643 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13644 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
13645 pub vel: [f32; 3],
13646 #[doc = "linear target acceleration (0,0,0) for unknown"]
13647 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13648 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
13649 pub acc: [f32; 3],
13650 #[doc = "(0 0 0 0 for unknown)"]
13651 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13652 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
13653 pub attitude_q: [f32; 4],
13654 #[doc = "(0 0 0 for unknown)"]
13655 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13656 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
13657 pub rates: [f32; 3],
13658 #[doc = "eph epv"]
13659 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13660 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
13661 pub position_cov: [f32; 3],
13662 #[doc = "bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3)"]
13663 pub est_capabilities: u8,
13664}
13665impl FOLLOW_TARGET_DATA {
13666 pub const ENCODED_LEN: usize = 93usize;
13667 pub const DEFAULT: Self = Self {
13668 timestamp: 0_u64,
13669 custom_state: 0_u64,
13670 lat: 0_i32,
13671 lon: 0_i32,
13672 alt: 0.0_f32,
13673 vel: [0.0_f32; 3usize],
13674 acc: [0.0_f32; 3usize],
13675 attitude_q: [0.0_f32; 4usize],
13676 rates: [0.0_f32; 3usize],
13677 position_cov: [0.0_f32; 3usize],
13678 est_capabilities: 0_u8,
13679 };
13680 #[cfg(feature = "arbitrary")]
13681 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13682 use arbitrary::{Arbitrary, Unstructured};
13683 let mut buf = [0u8; 1024];
13684 rng.fill_bytes(&mut buf);
13685 let mut unstructured = Unstructured::new(&buf);
13686 Self::arbitrary(&mut unstructured).unwrap_or_default()
13687 }
13688}
13689impl Default for FOLLOW_TARGET_DATA {
13690 fn default() -> Self {
13691 Self::DEFAULT.clone()
13692 }
13693}
13694impl MessageData for FOLLOW_TARGET_DATA {
13695 type Message = MavMessage;
13696 const ID: u32 = 144u32;
13697 const NAME: &'static str = "FOLLOW_TARGET";
13698 const EXTRA_CRC: u8 = 127u8;
13699 const ENCODED_LEN: usize = 93usize;
13700 fn deser(
13701 _version: MavlinkVersion,
13702 __input: &[u8],
13703 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13704 let avail_len = __input.len();
13705 let mut payload_buf = [0; Self::ENCODED_LEN];
13706 let mut buf = if avail_len < Self::ENCODED_LEN {
13707 payload_buf[0..avail_len].copy_from_slice(__input);
13708 Bytes::new(&payload_buf)
13709 } else {
13710 Bytes::new(__input)
13711 };
13712 let mut __struct = Self::default();
13713 __struct.timestamp = buf.get_u64_le()?;
13714 __struct.custom_state = buf.get_u64_le()?;
13715 __struct.lat = buf.get_i32_le()?;
13716 __struct.lon = buf.get_i32_le()?;
13717 __struct.alt = buf.get_f32_le()?;
13718 for v in &mut __struct.vel {
13719 let val = buf.get_f32_le()?;
13720 *v = val;
13721 }
13722 for v in &mut __struct.acc {
13723 let val = buf.get_f32_le()?;
13724 *v = val;
13725 }
13726 for v in &mut __struct.attitude_q {
13727 let val = buf.get_f32_le()?;
13728 *v = val;
13729 }
13730 for v in &mut __struct.rates {
13731 let val = buf.get_f32_le()?;
13732 *v = val;
13733 }
13734 for v in &mut __struct.position_cov {
13735 let val = buf.get_f32_le()?;
13736 *v = val;
13737 }
13738 __struct.est_capabilities = buf.get_u8()?;
13739 Ok(__struct)
13740 }
13741 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13742 let mut __tmp = BytesMut::new(bytes);
13743 #[allow(clippy::absurd_extreme_comparisons)]
13744 #[allow(unused_comparisons)]
13745 if __tmp.remaining() < Self::ENCODED_LEN {
13746 panic!(
13747 "buffer is too small (need {} bytes, but got {})",
13748 Self::ENCODED_LEN,
13749 __tmp.remaining(),
13750 )
13751 }
13752 __tmp.put_u64_le(self.timestamp);
13753 __tmp.put_u64_le(self.custom_state);
13754 __tmp.put_i32_le(self.lat);
13755 __tmp.put_i32_le(self.lon);
13756 __tmp.put_f32_le(self.alt);
13757 for val in &self.vel {
13758 __tmp.put_f32_le(*val);
13759 }
13760 for val in &self.acc {
13761 __tmp.put_f32_le(*val);
13762 }
13763 for val in &self.attitude_q {
13764 __tmp.put_f32_le(*val);
13765 }
13766 for val in &self.rates {
13767 __tmp.put_f32_le(*val);
13768 }
13769 for val in &self.position_cov {
13770 __tmp.put_f32_le(*val);
13771 }
13772 __tmp.put_u8(self.est_capabilities);
13773 if matches!(version, MavlinkVersion::V2) {
13774 let len = __tmp.len();
13775 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13776 } else {
13777 __tmp.len()
13778 }
13779 }
13780}
13781#[doc = "Fuel status. This message provides \"generic\" fuel level information for in a GCS and for triggering failsafes in an autopilot. The fuel type and associated units for fields in this message are defined in the enum MAV_FUEL_TYPE. The reported `consumed_fuel` and `remaining_fuel` must only be supplied if measured: they must not be inferred from the `maximum_fuel` and the other value. A recipient can assume that if these fields are supplied they are accurate. If not provided, the recipient can infer `remaining_fuel` from `maximum_fuel` and `consumed_fuel` on the assumption that the fuel was initially at its maximum (this is what battery monitors assume). Note however that this is an assumption, and the UI should prompt the user appropriately (i.e. notify user that they should fill the tank before boot). This kind of information may also be sent in fuel-specific messages such as BATTERY_STATUS_V2. If both messages are sent for the same fuel system, the ids and corresponding information must match. This should be streamed (nominally at 0.1 Hz)."]
13782#[doc = ""]
13783#[doc = "ID: 371"]
13784#[derive(Debug, Clone, PartialEq)]
13785#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13786#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13787#[cfg_attr(feature = "ts", derive(TS))]
13788#[cfg_attr(feature = "ts", ts(export))]
13789pub struct FUEL_STATUS_DATA {
13790 #[doc = "Capacity when full. Must be provided."]
13791 pub maximum_fuel: f32,
13792 #[doc = "Consumed fuel (measured). This value should not be inferred: if not measured set to NaN. NaN: field not provided."]
13793 pub consumed_fuel: f32,
13794 #[doc = "Remaining fuel until empty (measured). The value should not be inferred: if not measured set to NaN. NaN: field not provided."]
13795 pub remaining_fuel: f32,
13796 #[doc = "Positive value when emptying/using, and negative if filling/replacing. NaN: field not provided."]
13797 pub flow_rate: f32,
13798 #[doc = "Fuel temperature. NaN: field not provided."]
13799 pub temperature: f32,
13800 #[doc = "Fuel type. Defines units for fuel capacity and consumption fields above."]
13801 pub fuel_type: MavFuelType,
13802 #[doc = "Fuel ID. Must match ID of other messages for same fuel system, such as BATTERY_STATUS_V2."]
13803 pub id: u8,
13804 #[doc = "Percentage of remaining fuel, relative to full. Values: [0-100], UINT8_MAX: field not provided."]
13805 pub percent_remaining: u8,
13806}
13807impl FUEL_STATUS_DATA {
13808 pub const ENCODED_LEN: usize = 26usize;
13809 pub const DEFAULT: Self = Self {
13810 maximum_fuel: 0.0_f32,
13811 consumed_fuel: 0.0_f32,
13812 remaining_fuel: 0.0_f32,
13813 flow_rate: 0.0_f32,
13814 temperature: 0.0_f32,
13815 fuel_type: MavFuelType::DEFAULT,
13816 id: 0_u8,
13817 percent_remaining: 0_u8,
13818 };
13819 #[cfg(feature = "arbitrary")]
13820 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13821 use arbitrary::{Arbitrary, Unstructured};
13822 let mut buf = [0u8; 1024];
13823 rng.fill_bytes(&mut buf);
13824 let mut unstructured = Unstructured::new(&buf);
13825 Self::arbitrary(&mut unstructured).unwrap_or_default()
13826 }
13827}
13828impl Default for FUEL_STATUS_DATA {
13829 fn default() -> Self {
13830 Self::DEFAULT.clone()
13831 }
13832}
13833impl MessageData for FUEL_STATUS_DATA {
13834 type Message = MavMessage;
13835 const ID: u32 = 371u32;
13836 const NAME: &'static str = "FUEL_STATUS";
13837 const EXTRA_CRC: u8 = 10u8;
13838 const ENCODED_LEN: usize = 26usize;
13839 fn deser(
13840 _version: MavlinkVersion,
13841 __input: &[u8],
13842 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13843 let avail_len = __input.len();
13844 let mut payload_buf = [0; Self::ENCODED_LEN];
13845 let mut buf = if avail_len < Self::ENCODED_LEN {
13846 payload_buf[0..avail_len].copy_from_slice(__input);
13847 Bytes::new(&payload_buf)
13848 } else {
13849 Bytes::new(__input)
13850 };
13851 let mut __struct = Self::default();
13852 __struct.maximum_fuel = buf.get_f32_le()?;
13853 __struct.consumed_fuel = buf.get_f32_le()?;
13854 __struct.remaining_fuel = buf.get_f32_le()?;
13855 __struct.flow_rate = buf.get_f32_le()?;
13856 __struct.temperature = buf.get_f32_le()?;
13857 let tmp = buf.get_u32_le()?;
13858 __struct.fuel_type = FromPrimitive::from_u32(tmp).ok_or(
13859 ::mavlink_core::error::ParserError::InvalidEnum {
13860 enum_type: "MavFuelType",
13861 value: tmp as u64,
13862 },
13863 )?;
13864 __struct.id = buf.get_u8()?;
13865 __struct.percent_remaining = buf.get_u8()?;
13866 Ok(__struct)
13867 }
13868 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13869 let mut __tmp = BytesMut::new(bytes);
13870 #[allow(clippy::absurd_extreme_comparisons)]
13871 #[allow(unused_comparisons)]
13872 if __tmp.remaining() < Self::ENCODED_LEN {
13873 panic!(
13874 "buffer is too small (need {} bytes, but got {})",
13875 Self::ENCODED_LEN,
13876 __tmp.remaining(),
13877 )
13878 }
13879 __tmp.put_f32_le(self.maximum_fuel);
13880 __tmp.put_f32_le(self.consumed_fuel);
13881 __tmp.put_f32_le(self.remaining_fuel);
13882 __tmp.put_f32_le(self.flow_rate);
13883 __tmp.put_f32_le(self.temperature);
13884 __tmp.put_u32_le(self.fuel_type as u32);
13885 __tmp.put_u8(self.id);
13886 __tmp.put_u8(self.percent_remaining);
13887 if matches!(version, MavlinkVersion::V2) {
13888 let len = __tmp.len();
13889 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13890 } else {
13891 __tmp.len()
13892 }
13893 }
13894}
13895#[doc = "Telemetry of power generation system. Alternator or mechanical generator."]
13896#[doc = ""]
13897#[doc = "ID: 373"]
13898#[derive(Debug, Clone, PartialEq)]
13899#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13900#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13901#[cfg_attr(feature = "ts", derive(TS))]
13902#[cfg_attr(feature = "ts", ts(export))]
13903pub struct GENERATOR_STATUS_DATA {
13904 #[doc = "Status flags."]
13905 pub status: MavGeneratorStatusFlag,
13906 #[doc = "Current into/out of battery. Positive for out. Negative for in. NaN: field not provided."]
13907 pub battery_current: f32,
13908 #[doc = "Current going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided"]
13909 pub load_current: f32,
13910 #[doc = "The power being generated. NaN: field not provided"]
13911 pub power_generated: f32,
13912 #[doc = "Voltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus."]
13913 pub bus_voltage: f32,
13914 #[doc = "The target battery current. Positive for out. Negative for in. NaN: field not provided"]
13915 pub bat_current_setpoint: f32,
13916 #[doc = "Seconds this generator has run since it was rebooted. UINT32_MAX: field not provided."]
13917 pub runtime: u32,
13918 #[doc = "Seconds until this generator requires maintenance. A negative value indicates maintenance is past-due. INT32_MAX: field not provided."]
13919 pub time_until_maintenance: i32,
13920 #[doc = "Speed of electrical generator or alternator. UINT16_MAX: field not provided."]
13921 pub generator_speed: u16,
13922 #[doc = "The temperature of the rectifier or power converter. INT16_MAX: field not provided."]
13923 pub rectifier_temperature: i16,
13924 #[doc = "The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided."]
13925 pub generator_temperature: i16,
13926}
13927impl GENERATOR_STATUS_DATA {
13928 pub const ENCODED_LEN: usize = 42usize;
13929 pub const DEFAULT: Self = Self {
13930 status: MavGeneratorStatusFlag::DEFAULT,
13931 battery_current: 0.0_f32,
13932 load_current: 0.0_f32,
13933 power_generated: 0.0_f32,
13934 bus_voltage: 0.0_f32,
13935 bat_current_setpoint: 0.0_f32,
13936 runtime: 0_u32,
13937 time_until_maintenance: 0_i32,
13938 generator_speed: 0_u16,
13939 rectifier_temperature: 0_i16,
13940 generator_temperature: 0_i16,
13941 };
13942 #[cfg(feature = "arbitrary")]
13943 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13944 use arbitrary::{Arbitrary, Unstructured};
13945 let mut buf = [0u8; 1024];
13946 rng.fill_bytes(&mut buf);
13947 let mut unstructured = Unstructured::new(&buf);
13948 Self::arbitrary(&mut unstructured).unwrap_or_default()
13949 }
13950}
13951impl Default for GENERATOR_STATUS_DATA {
13952 fn default() -> Self {
13953 Self::DEFAULT.clone()
13954 }
13955}
13956impl MessageData for GENERATOR_STATUS_DATA {
13957 type Message = MavMessage;
13958 const ID: u32 = 373u32;
13959 const NAME: &'static str = "GENERATOR_STATUS";
13960 const EXTRA_CRC: u8 = 117u8;
13961 const ENCODED_LEN: usize = 42usize;
13962 fn deser(
13963 _version: MavlinkVersion,
13964 __input: &[u8],
13965 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13966 let avail_len = __input.len();
13967 let mut payload_buf = [0; Self::ENCODED_LEN];
13968 let mut buf = if avail_len < Self::ENCODED_LEN {
13969 payload_buf[0..avail_len].copy_from_slice(__input);
13970 Bytes::new(&payload_buf)
13971 } else {
13972 Bytes::new(__input)
13973 };
13974 let mut __struct = Self::default();
13975 let tmp = buf.get_u64_le()?;
13976 __struct.status =
13977 MavGeneratorStatusFlag::from_bits(tmp as <MavGeneratorStatusFlag as Flags>::Bits)
13978 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
13979 flag_type: "MavGeneratorStatusFlag",
13980 value: tmp as u64,
13981 })?;
13982 __struct.battery_current = buf.get_f32_le()?;
13983 __struct.load_current = buf.get_f32_le()?;
13984 __struct.power_generated = buf.get_f32_le()?;
13985 __struct.bus_voltage = buf.get_f32_le()?;
13986 __struct.bat_current_setpoint = buf.get_f32_le()?;
13987 __struct.runtime = buf.get_u32_le()?;
13988 __struct.time_until_maintenance = buf.get_i32_le()?;
13989 __struct.generator_speed = buf.get_u16_le()?;
13990 __struct.rectifier_temperature = buf.get_i16_le()?;
13991 __struct.generator_temperature = buf.get_i16_le()?;
13992 Ok(__struct)
13993 }
13994 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13995 let mut __tmp = BytesMut::new(bytes);
13996 #[allow(clippy::absurd_extreme_comparisons)]
13997 #[allow(unused_comparisons)]
13998 if __tmp.remaining() < Self::ENCODED_LEN {
13999 panic!(
14000 "buffer is too small (need {} bytes, but got {})",
14001 Self::ENCODED_LEN,
14002 __tmp.remaining(),
14003 )
14004 }
14005 __tmp.put_u64_le(self.status.bits() as u64);
14006 __tmp.put_f32_le(self.battery_current);
14007 __tmp.put_f32_le(self.load_current);
14008 __tmp.put_f32_le(self.power_generated);
14009 __tmp.put_f32_le(self.bus_voltage);
14010 __tmp.put_f32_le(self.bat_current_setpoint);
14011 __tmp.put_u32_le(self.runtime);
14012 __tmp.put_i32_le(self.time_until_maintenance);
14013 __tmp.put_u16_le(self.generator_speed);
14014 __tmp.put_i16_le(self.rectifier_temperature);
14015 __tmp.put_i16_le(self.generator_temperature);
14016 if matches!(version, MavlinkVersion::V2) {
14017 let len = __tmp.len();
14018 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14019 } else {
14020 __tmp.len()
14021 }
14022 }
14023}
14024#[doc = "Message reporting the status of a gimbal device. \t This message should be broadcast by a gimbal device component at a low regular rate (e.g. 5 Hz). \t For the angles encoded in the quaternion and the angular velocities holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). \t If neither of these flags are set, then (for backwards compatibility) it holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), \t else they are relative to the vehicle heading (vehicle frame). \t Other conditions of the flags are not allowed. \t The quaternion and angular velocities in the other frame can be calculated from delta_yaw and delta_yaw_velocity as \t q_earth = q_delta_yaw * q_vehicle and w_earth = w_delta_yaw_velocity + w_vehicle (if not NaN). \t If neither the GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME nor the GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME flag is set, \t then (for backwards compatibility) the data in the delta_yaw and delta_yaw_velocity fields are to be ignored. \t New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME, \t and always should set delta_yaw and delta_yaw_velocity either to the proper value or NaN."]
14025#[doc = ""]
14026#[doc = "ID: 285"]
14027#[derive(Debug, Clone, PartialEq)]
14028#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14029#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14030#[cfg_attr(feature = "ts", derive(TS))]
14031#[cfg_attr(feature = "ts", ts(export))]
14032pub struct GIMBAL_DEVICE_ATTITUDE_STATUS_DATA {
14033 #[doc = "Timestamp (time since system boot)."]
14034 pub time_boot_ms: u32,
14035 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description."]
14036 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14037 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
14038 pub q: [f32; 4],
14039 #[doc = "X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN if unknown."]
14040 pub angular_velocity_x: f32,
14041 #[doc = "Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN if unknown."]
14042 pub angular_velocity_y: f32,
14043 #[doc = "Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN if unknown."]
14044 pub angular_velocity_z: f32,
14045 #[doc = "Failure flags (0 for no failure)"]
14046 pub failure_flags: GimbalDeviceErrorFlags,
14047 #[doc = "Current gimbal flags set."]
14048 pub flags: GimbalDeviceFlags,
14049 #[doc = "System ID"]
14050 pub target_system: u8,
14051 #[doc = "Component ID"]
14052 pub target_component: u8,
14053 #[doc = "Yaw angle relating the quaternions in earth and body frames (see message description). NaN if unknown."]
14054 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
14055 pub delta_yaw: f32,
14056 #[doc = "Yaw angular velocity relating the angular velocities in earth and body frames (see message description). NaN if unknown."]
14057 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
14058 pub delta_yaw_velocity: f32,
14059 #[doc = "This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set a number between 1-6. If the component ID is separate, this field is not required and must be set to 0."]
14060 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
14061 pub gimbal_device_id: u8,
14062}
14063impl GIMBAL_DEVICE_ATTITUDE_STATUS_DATA {
14064 pub const ENCODED_LEN: usize = 49usize;
14065 pub const DEFAULT: Self = Self {
14066 time_boot_ms: 0_u32,
14067 q: [0.0_f32; 4usize],
14068 angular_velocity_x: 0.0_f32,
14069 angular_velocity_y: 0.0_f32,
14070 angular_velocity_z: 0.0_f32,
14071 failure_flags: GimbalDeviceErrorFlags::DEFAULT,
14072 flags: GimbalDeviceFlags::DEFAULT,
14073 target_system: 0_u8,
14074 target_component: 0_u8,
14075 delta_yaw: 0.0_f32,
14076 delta_yaw_velocity: 0.0_f32,
14077 gimbal_device_id: 0_u8,
14078 };
14079 #[cfg(feature = "arbitrary")]
14080 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14081 use arbitrary::{Arbitrary, Unstructured};
14082 let mut buf = [0u8; 1024];
14083 rng.fill_bytes(&mut buf);
14084 let mut unstructured = Unstructured::new(&buf);
14085 Self::arbitrary(&mut unstructured).unwrap_or_default()
14086 }
14087}
14088impl Default for GIMBAL_DEVICE_ATTITUDE_STATUS_DATA {
14089 fn default() -> Self {
14090 Self::DEFAULT.clone()
14091 }
14092}
14093impl MessageData for GIMBAL_DEVICE_ATTITUDE_STATUS_DATA {
14094 type Message = MavMessage;
14095 const ID: u32 = 285u32;
14096 const NAME: &'static str = "GIMBAL_DEVICE_ATTITUDE_STATUS";
14097 const EXTRA_CRC: u8 = 137u8;
14098 const ENCODED_LEN: usize = 49usize;
14099 fn deser(
14100 _version: MavlinkVersion,
14101 __input: &[u8],
14102 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14103 let avail_len = __input.len();
14104 let mut payload_buf = [0; Self::ENCODED_LEN];
14105 let mut buf = if avail_len < Self::ENCODED_LEN {
14106 payload_buf[0..avail_len].copy_from_slice(__input);
14107 Bytes::new(&payload_buf)
14108 } else {
14109 Bytes::new(__input)
14110 };
14111 let mut __struct = Self::default();
14112 __struct.time_boot_ms = buf.get_u32_le()?;
14113 for v in &mut __struct.q {
14114 let val = buf.get_f32_le()?;
14115 *v = val;
14116 }
14117 __struct.angular_velocity_x = buf.get_f32_le()?;
14118 __struct.angular_velocity_y = buf.get_f32_le()?;
14119 __struct.angular_velocity_z = buf.get_f32_le()?;
14120 let tmp = buf.get_u32_le()?;
14121 __struct.failure_flags =
14122 GimbalDeviceErrorFlags::from_bits(tmp as <GimbalDeviceErrorFlags as Flags>::Bits)
14123 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
14124 flag_type: "GimbalDeviceErrorFlags",
14125 value: tmp as u64,
14126 })?;
14127 let tmp = buf.get_u16_le()?;
14128 __struct.flags = GimbalDeviceFlags::from_bits(tmp as <GimbalDeviceFlags as Flags>::Bits)
14129 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
14130 flag_type: "GimbalDeviceFlags",
14131 value: tmp as u64,
14132 })?;
14133 __struct.target_system = buf.get_u8()?;
14134 __struct.target_component = buf.get_u8()?;
14135 __struct.delta_yaw = buf.get_f32_le()?;
14136 __struct.delta_yaw_velocity = buf.get_f32_le()?;
14137 __struct.gimbal_device_id = buf.get_u8()?;
14138 Ok(__struct)
14139 }
14140 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14141 let mut __tmp = BytesMut::new(bytes);
14142 #[allow(clippy::absurd_extreme_comparisons)]
14143 #[allow(unused_comparisons)]
14144 if __tmp.remaining() < Self::ENCODED_LEN {
14145 panic!(
14146 "buffer is too small (need {} bytes, but got {})",
14147 Self::ENCODED_LEN,
14148 __tmp.remaining(),
14149 )
14150 }
14151 __tmp.put_u32_le(self.time_boot_ms);
14152 for val in &self.q {
14153 __tmp.put_f32_le(*val);
14154 }
14155 __tmp.put_f32_le(self.angular_velocity_x);
14156 __tmp.put_f32_le(self.angular_velocity_y);
14157 __tmp.put_f32_le(self.angular_velocity_z);
14158 __tmp.put_u32_le(self.failure_flags.bits() as u32);
14159 __tmp.put_u16_le(self.flags.bits() as u16);
14160 __tmp.put_u8(self.target_system);
14161 __tmp.put_u8(self.target_component);
14162 if matches!(version, MavlinkVersion::V2) {
14163 __tmp.put_f32_le(self.delta_yaw);
14164 __tmp.put_f32_le(self.delta_yaw_velocity);
14165 __tmp.put_u8(self.gimbal_device_id);
14166 let len = __tmp.len();
14167 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14168 } else {
14169 __tmp.len()
14170 }
14171 }
14172}
14173#[doc = "Information about a low level gimbal. This message should be requested by the gimbal manager or a ground station using MAV_CMD_REQUEST_MESSAGE. The maximum angles and rates are the limits by hardware. However, the limits by software used are likely different/smaller and dependent on mode/settings/etc.."]
14174#[doc = ""]
14175#[doc = "ID: 283"]
14176#[derive(Debug, Clone, PartialEq)]
14177#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14178#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14179#[cfg_attr(feature = "ts", derive(TS))]
14180#[cfg_attr(feature = "ts", ts(export))]
14181pub struct GIMBAL_DEVICE_INFORMATION_DATA {
14182 #[doc = "UID of gimbal hardware (0 if unknown)."]
14183 pub uid: u64,
14184 #[doc = "Timestamp (time since system boot)."]
14185 pub time_boot_ms: u32,
14186 #[doc = "Version of the gimbal firmware, encoded as: (Dev&0xff)<<24 | (Patch&0xff)<<16 | (Minor&0xff)<<8 | (Major&0xff)."]
14187 pub firmware_version: u32,
14188 #[doc = "Version of the gimbal hardware, encoded as: (Dev&0xff)<<24 | (Patch&0xff)<<16 | (Minor&0xff)<<8 | (Major&0xff)."]
14189 pub hardware_version: u32,
14190 #[doc = "Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown."]
14191 pub roll_min: f32,
14192 #[doc = "Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown."]
14193 pub roll_max: f32,
14194 #[doc = "Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown."]
14195 pub pitch_min: f32,
14196 #[doc = "Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown."]
14197 pub pitch_max: f32,
14198 #[doc = "Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown."]
14199 pub yaw_min: f32,
14200 #[doc = "Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown."]
14201 pub yaw_max: f32,
14202 #[doc = "Bitmap of gimbal capability flags."]
14203 pub cap_flags: GimbalDeviceCapFlags,
14204 #[doc = "Bitmap for use for gimbal-specific capability flags."]
14205 pub custom_cap_flags: u16,
14206 #[doc = "Name of the gimbal vendor."]
14207 #[cfg_attr(feature = "ts", ts(type = "string"))]
14208 pub vendor_name: CharArray<32>,
14209 #[doc = "Name of the gimbal model."]
14210 #[cfg_attr(feature = "ts", ts(type = "string"))]
14211 pub model_name: CharArray<32>,
14212 #[doc = "Custom name of the gimbal given to it by the user."]
14213 #[cfg_attr(feature = "ts", ts(type = "string"))]
14214 pub custom_name: CharArray<32>,
14215 #[doc = "This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0."]
14216 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
14217 pub gimbal_device_id: u8,
14218}
14219impl GIMBAL_DEVICE_INFORMATION_DATA {
14220 pub const ENCODED_LEN: usize = 145usize;
14221 pub const DEFAULT: Self = Self {
14222 uid: 0_u64,
14223 time_boot_ms: 0_u32,
14224 firmware_version: 0_u32,
14225 hardware_version: 0_u32,
14226 roll_min: 0.0_f32,
14227 roll_max: 0.0_f32,
14228 pitch_min: 0.0_f32,
14229 pitch_max: 0.0_f32,
14230 yaw_min: 0.0_f32,
14231 yaw_max: 0.0_f32,
14232 cap_flags: GimbalDeviceCapFlags::DEFAULT,
14233 custom_cap_flags: 0_u16,
14234 vendor_name: CharArray::new([0_u8; 32usize]),
14235 model_name: CharArray::new([0_u8; 32usize]),
14236 custom_name: CharArray::new([0_u8; 32usize]),
14237 gimbal_device_id: 0_u8,
14238 };
14239 #[cfg(feature = "arbitrary")]
14240 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14241 use arbitrary::{Arbitrary, Unstructured};
14242 let mut buf = [0u8; 1024];
14243 rng.fill_bytes(&mut buf);
14244 let mut unstructured = Unstructured::new(&buf);
14245 Self::arbitrary(&mut unstructured).unwrap_or_default()
14246 }
14247}
14248impl Default for GIMBAL_DEVICE_INFORMATION_DATA {
14249 fn default() -> Self {
14250 Self::DEFAULT.clone()
14251 }
14252}
14253impl MessageData for GIMBAL_DEVICE_INFORMATION_DATA {
14254 type Message = MavMessage;
14255 const ID: u32 = 283u32;
14256 const NAME: &'static str = "GIMBAL_DEVICE_INFORMATION";
14257 const EXTRA_CRC: u8 = 74u8;
14258 const ENCODED_LEN: usize = 145usize;
14259 fn deser(
14260 _version: MavlinkVersion,
14261 __input: &[u8],
14262 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14263 let avail_len = __input.len();
14264 let mut payload_buf = [0; Self::ENCODED_LEN];
14265 let mut buf = if avail_len < Self::ENCODED_LEN {
14266 payload_buf[0..avail_len].copy_from_slice(__input);
14267 Bytes::new(&payload_buf)
14268 } else {
14269 Bytes::new(__input)
14270 };
14271 let mut __struct = Self::default();
14272 __struct.uid = buf.get_u64_le()?;
14273 __struct.time_boot_ms = buf.get_u32_le()?;
14274 __struct.firmware_version = buf.get_u32_le()?;
14275 __struct.hardware_version = buf.get_u32_le()?;
14276 __struct.roll_min = buf.get_f32_le()?;
14277 __struct.roll_max = buf.get_f32_le()?;
14278 __struct.pitch_min = buf.get_f32_le()?;
14279 __struct.pitch_max = buf.get_f32_le()?;
14280 __struct.yaw_min = buf.get_f32_le()?;
14281 __struct.yaw_max = buf.get_f32_le()?;
14282 let tmp = buf.get_u16_le()?;
14283 __struct.cap_flags = GimbalDeviceCapFlags::from_bits(
14284 tmp as <GimbalDeviceCapFlags as Flags>::Bits,
14285 )
14286 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
14287 flag_type: "GimbalDeviceCapFlags",
14288 value: tmp as u64,
14289 })?;
14290 __struct.custom_cap_flags = buf.get_u16_le()?;
14291 let mut tmp = [0_u8; 32usize];
14292 for v in &mut tmp {
14293 *v = buf.get_u8()?;
14294 }
14295 __struct.vendor_name = CharArray::new(tmp);
14296 let mut tmp = [0_u8; 32usize];
14297 for v in &mut tmp {
14298 *v = buf.get_u8()?;
14299 }
14300 __struct.model_name = CharArray::new(tmp);
14301 let mut tmp = [0_u8; 32usize];
14302 for v in &mut tmp {
14303 *v = buf.get_u8()?;
14304 }
14305 __struct.custom_name = CharArray::new(tmp);
14306 __struct.gimbal_device_id = buf.get_u8()?;
14307 Ok(__struct)
14308 }
14309 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14310 let mut __tmp = BytesMut::new(bytes);
14311 #[allow(clippy::absurd_extreme_comparisons)]
14312 #[allow(unused_comparisons)]
14313 if __tmp.remaining() < Self::ENCODED_LEN {
14314 panic!(
14315 "buffer is too small (need {} bytes, but got {})",
14316 Self::ENCODED_LEN,
14317 __tmp.remaining(),
14318 )
14319 }
14320 __tmp.put_u64_le(self.uid);
14321 __tmp.put_u32_le(self.time_boot_ms);
14322 __tmp.put_u32_le(self.firmware_version);
14323 __tmp.put_u32_le(self.hardware_version);
14324 __tmp.put_f32_le(self.roll_min);
14325 __tmp.put_f32_le(self.roll_max);
14326 __tmp.put_f32_le(self.pitch_min);
14327 __tmp.put_f32_le(self.pitch_max);
14328 __tmp.put_f32_le(self.yaw_min);
14329 __tmp.put_f32_le(self.yaw_max);
14330 __tmp.put_u16_le(self.cap_flags.bits() as u16);
14331 __tmp.put_u16_le(self.custom_cap_flags);
14332 for val in &self.vendor_name {
14333 __tmp.put_u8(*val);
14334 }
14335 for val in &self.model_name {
14336 __tmp.put_u8(*val);
14337 }
14338 for val in &self.custom_name {
14339 __tmp.put_u8(*val);
14340 }
14341 if matches!(version, MavlinkVersion::V2) {
14342 __tmp.put_u8(self.gimbal_device_id);
14343 let len = __tmp.len();
14344 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14345 } else {
14346 __tmp.len()
14347 }
14348 }
14349}
14350#[doc = "Low level message to control a gimbal device's attitude. \t This message is to be sent from the gimbal manager to the gimbal device component. \t The quaternion and angular velocities can be set to NaN according to use case. \t For the angles encoded in the quaternion and the angular velocities holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). \t If neither of these flags are set, then (for backwards compatibility) it holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), \t else they are relative to the vehicle heading (vehicle frame). \t Setting both GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME and GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is not allowed. \t These rules are to ensure backwards compatibility. \t New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME."]
14351#[doc = ""]
14352#[doc = "ID: 284"]
14353#[derive(Debug, Clone, PartialEq)]
14354#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14355#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14356#[cfg_attr(feature = "ts", derive(TS))]
14357#[cfg_attr(feature = "ts", ts(export))]
14358pub struct GIMBAL_DEVICE_SET_ATTITUDE_DATA {
14359 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. Set fields to NaN to be ignored."]
14360 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14361 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
14362 pub q: [f32; 4],
14363 #[doc = "X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN to be ignored."]
14364 pub angular_velocity_x: f32,
14365 #[doc = "Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN to be ignored."]
14366 pub angular_velocity_y: f32,
14367 #[doc = "Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN to be ignored."]
14368 pub angular_velocity_z: f32,
14369 #[doc = "Low level gimbal flags."]
14370 pub flags: GimbalDeviceFlags,
14371 #[doc = "System ID"]
14372 pub target_system: u8,
14373 #[doc = "Component ID"]
14374 pub target_component: u8,
14375}
14376impl GIMBAL_DEVICE_SET_ATTITUDE_DATA {
14377 pub const ENCODED_LEN: usize = 32usize;
14378 pub const DEFAULT: Self = Self {
14379 q: [0.0_f32; 4usize],
14380 angular_velocity_x: 0.0_f32,
14381 angular_velocity_y: 0.0_f32,
14382 angular_velocity_z: 0.0_f32,
14383 flags: GimbalDeviceFlags::DEFAULT,
14384 target_system: 0_u8,
14385 target_component: 0_u8,
14386 };
14387 #[cfg(feature = "arbitrary")]
14388 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14389 use arbitrary::{Arbitrary, Unstructured};
14390 let mut buf = [0u8; 1024];
14391 rng.fill_bytes(&mut buf);
14392 let mut unstructured = Unstructured::new(&buf);
14393 Self::arbitrary(&mut unstructured).unwrap_or_default()
14394 }
14395}
14396impl Default for GIMBAL_DEVICE_SET_ATTITUDE_DATA {
14397 fn default() -> Self {
14398 Self::DEFAULT.clone()
14399 }
14400}
14401impl MessageData for GIMBAL_DEVICE_SET_ATTITUDE_DATA {
14402 type Message = MavMessage;
14403 const ID: u32 = 284u32;
14404 const NAME: &'static str = "GIMBAL_DEVICE_SET_ATTITUDE";
14405 const EXTRA_CRC: u8 = 99u8;
14406 const ENCODED_LEN: usize = 32usize;
14407 fn deser(
14408 _version: MavlinkVersion,
14409 __input: &[u8],
14410 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14411 let avail_len = __input.len();
14412 let mut payload_buf = [0; Self::ENCODED_LEN];
14413 let mut buf = if avail_len < Self::ENCODED_LEN {
14414 payload_buf[0..avail_len].copy_from_slice(__input);
14415 Bytes::new(&payload_buf)
14416 } else {
14417 Bytes::new(__input)
14418 };
14419 let mut __struct = Self::default();
14420 for v in &mut __struct.q {
14421 let val = buf.get_f32_le()?;
14422 *v = val;
14423 }
14424 __struct.angular_velocity_x = buf.get_f32_le()?;
14425 __struct.angular_velocity_y = buf.get_f32_le()?;
14426 __struct.angular_velocity_z = buf.get_f32_le()?;
14427 let tmp = buf.get_u16_le()?;
14428 __struct.flags = GimbalDeviceFlags::from_bits(tmp as <GimbalDeviceFlags as Flags>::Bits)
14429 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
14430 flag_type: "GimbalDeviceFlags",
14431 value: tmp as u64,
14432 })?;
14433 __struct.target_system = buf.get_u8()?;
14434 __struct.target_component = buf.get_u8()?;
14435 Ok(__struct)
14436 }
14437 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14438 let mut __tmp = BytesMut::new(bytes);
14439 #[allow(clippy::absurd_extreme_comparisons)]
14440 #[allow(unused_comparisons)]
14441 if __tmp.remaining() < Self::ENCODED_LEN {
14442 panic!(
14443 "buffer is too small (need {} bytes, but got {})",
14444 Self::ENCODED_LEN,
14445 __tmp.remaining(),
14446 )
14447 }
14448 for val in &self.q {
14449 __tmp.put_f32_le(*val);
14450 }
14451 __tmp.put_f32_le(self.angular_velocity_x);
14452 __tmp.put_f32_le(self.angular_velocity_y);
14453 __tmp.put_f32_le(self.angular_velocity_z);
14454 __tmp.put_u16_le(self.flags.bits() as u16);
14455 __tmp.put_u8(self.target_system);
14456 __tmp.put_u8(self.target_component);
14457 if matches!(version, MavlinkVersion::V2) {
14458 let len = __tmp.len();
14459 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14460 } else {
14461 __tmp.len()
14462 }
14463 }
14464}
14465#[doc = "Information about a high level gimbal manager. This message should be requested by a ground station using MAV_CMD_REQUEST_MESSAGE."]
14466#[doc = ""]
14467#[doc = "ID: 280"]
14468#[derive(Debug, Clone, PartialEq)]
14469#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14470#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14471#[cfg_attr(feature = "ts", derive(TS))]
14472#[cfg_attr(feature = "ts", ts(export))]
14473pub struct GIMBAL_MANAGER_INFORMATION_DATA {
14474 #[doc = "Timestamp (time since system boot)."]
14475 pub time_boot_ms: u32,
14476 #[doc = "Bitmap of gimbal capability flags."]
14477 pub cap_flags: GimbalManagerCapFlags,
14478 #[doc = "Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left)"]
14479 pub roll_min: f32,
14480 #[doc = "Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left)"]
14481 pub roll_max: f32,
14482 #[doc = "Minimum pitch angle (positive: up, negative: down)"]
14483 pub pitch_min: f32,
14484 #[doc = "Maximum pitch angle (positive: up, negative: down)"]
14485 pub pitch_max: f32,
14486 #[doc = "Minimum yaw angle (positive: to the right, negative: to the left)"]
14487 pub yaw_min: f32,
14488 #[doc = "Maximum yaw angle (positive: to the right, negative: to the left)"]
14489 pub yaw_max: f32,
14490 #[doc = "Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal)."]
14491 pub gimbal_device_id: u8,
14492}
14493impl GIMBAL_MANAGER_INFORMATION_DATA {
14494 pub const ENCODED_LEN: usize = 33usize;
14495 pub const DEFAULT: Self = Self {
14496 time_boot_ms: 0_u32,
14497 cap_flags: GimbalManagerCapFlags::DEFAULT,
14498 roll_min: 0.0_f32,
14499 roll_max: 0.0_f32,
14500 pitch_min: 0.0_f32,
14501 pitch_max: 0.0_f32,
14502 yaw_min: 0.0_f32,
14503 yaw_max: 0.0_f32,
14504 gimbal_device_id: 0_u8,
14505 };
14506 #[cfg(feature = "arbitrary")]
14507 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14508 use arbitrary::{Arbitrary, Unstructured};
14509 let mut buf = [0u8; 1024];
14510 rng.fill_bytes(&mut buf);
14511 let mut unstructured = Unstructured::new(&buf);
14512 Self::arbitrary(&mut unstructured).unwrap_or_default()
14513 }
14514}
14515impl Default for GIMBAL_MANAGER_INFORMATION_DATA {
14516 fn default() -> Self {
14517 Self::DEFAULT.clone()
14518 }
14519}
14520impl MessageData for GIMBAL_MANAGER_INFORMATION_DATA {
14521 type Message = MavMessage;
14522 const ID: u32 = 280u32;
14523 const NAME: &'static str = "GIMBAL_MANAGER_INFORMATION";
14524 const EXTRA_CRC: u8 = 70u8;
14525 const ENCODED_LEN: usize = 33usize;
14526 fn deser(
14527 _version: MavlinkVersion,
14528 __input: &[u8],
14529 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14530 let avail_len = __input.len();
14531 let mut payload_buf = [0; Self::ENCODED_LEN];
14532 let mut buf = if avail_len < Self::ENCODED_LEN {
14533 payload_buf[0..avail_len].copy_from_slice(__input);
14534 Bytes::new(&payload_buf)
14535 } else {
14536 Bytes::new(__input)
14537 };
14538 let mut __struct = Self::default();
14539 __struct.time_boot_ms = buf.get_u32_le()?;
14540 let tmp = buf.get_u32_le()?;
14541 __struct.cap_flags = GimbalManagerCapFlags::from_bits(
14542 tmp as <GimbalManagerCapFlags as Flags>::Bits,
14543 )
14544 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
14545 flag_type: "GimbalManagerCapFlags",
14546 value: tmp as u64,
14547 })?;
14548 __struct.roll_min = buf.get_f32_le()?;
14549 __struct.roll_max = buf.get_f32_le()?;
14550 __struct.pitch_min = buf.get_f32_le()?;
14551 __struct.pitch_max = buf.get_f32_le()?;
14552 __struct.yaw_min = buf.get_f32_le()?;
14553 __struct.yaw_max = buf.get_f32_le()?;
14554 __struct.gimbal_device_id = buf.get_u8()?;
14555 Ok(__struct)
14556 }
14557 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14558 let mut __tmp = BytesMut::new(bytes);
14559 #[allow(clippy::absurd_extreme_comparisons)]
14560 #[allow(unused_comparisons)]
14561 if __tmp.remaining() < Self::ENCODED_LEN {
14562 panic!(
14563 "buffer is too small (need {} bytes, but got {})",
14564 Self::ENCODED_LEN,
14565 __tmp.remaining(),
14566 )
14567 }
14568 __tmp.put_u32_le(self.time_boot_ms);
14569 __tmp.put_u32_le(self.cap_flags.bits() as u32);
14570 __tmp.put_f32_le(self.roll_min);
14571 __tmp.put_f32_le(self.roll_max);
14572 __tmp.put_f32_le(self.pitch_min);
14573 __tmp.put_f32_le(self.pitch_max);
14574 __tmp.put_f32_le(self.yaw_min);
14575 __tmp.put_f32_le(self.yaw_max);
14576 __tmp.put_u8(self.gimbal_device_id);
14577 if matches!(version, MavlinkVersion::V2) {
14578 let len = __tmp.len();
14579 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14580 } else {
14581 __tmp.len()
14582 }
14583 }
14584}
14585#[doc = "High level message to control a gimbal's attitude. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case."]
14586#[doc = ""]
14587#[doc = "ID: 282"]
14588#[derive(Debug, Clone, PartialEq)]
14589#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14590#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14591#[cfg_attr(feature = "ts", derive(TS))]
14592#[cfg_attr(feature = "ts", ts(export))]
14593pub struct GIMBAL_MANAGER_SET_ATTITUDE_DATA {
14594 #[doc = "High level gimbal manager flags to use."]
14595 pub flags: GimbalManagerFlags,
14596 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set)"]
14597 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14598 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
14599 pub q: [f32; 4],
14600 #[doc = "X component of angular velocity, positive is rolling to the right, NaN to be ignored."]
14601 pub angular_velocity_x: f32,
14602 #[doc = "Y component of angular velocity, positive is pitching up, NaN to be ignored."]
14603 pub angular_velocity_y: f32,
14604 #[doc = "Z component of angular velocity, positive is yawing to the right, NaN to be ignored."]
14605 pub angular_velocity_z: f32,
14606 #[doc = "System ID"]
14607 pub target_system: u8,
14608 #[doc = "Component ID"]
14609 pub target_component: u8,
14610 #[doc = "Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals)."]
14611 pub gimbal_device_id: u8,
14612}
14613impl GIMBAL_MANAGER_SET_ATTITUDE_DATA {
14614 pub const ENCODED_LEN: usize = 35usize;
14615 pub const DEFAULT: Self = Self {
14616 flags: GimbalManagerFlags::DEFAULT,
14617 q: [0.0_f32; 4usize],
14618 angular_velocity_x: 0.0_f32,
14619 angular_velocity_y: 0.0_f32,
14620 angular_velocity_z: 0.0_f32,
14621 target_system: 0_u8,
14622 target_component: 0_u8,
14623 gimbal_device_id: 0_u8,
14624 };
14625 #[cfg(feature = "arbitrary")]
14626 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14627 use arbitrary::{Arbitrary, Unstructured};
14628 let mut buf = [0u8; 1024];
14629 rng.fill_bytes(&mut buf);
14630 let mut unstructured = Unstructured::new(&buf);
14631 Self::arbitrary(&mut unstructured).unwrap_or_default()
14632 }
14633}
14634impl Default for GIMBAL_MANAGER_SET_ATTITUDE_DATA {
14635 fn default() -> Self {
14636 Self::DEFAULT.clone()
14637 }
14638}
14639impl MessageData for GIMBAL_MANAGER_SET_ATTITUDE_DATA {
14640 type Message = MavMessage;
14641 const ID: u32 = 282u32;
14642 const NAME: &'static str = "GIMBAL_MANAGER_SET_ATTITUDE";
14643 const EXTRA_CRC: u8 = 123u8;
14644 const ENCODED_LEN: usize = 35usize;
14645 fn deser(
14646 _version: MavlinkVersion,
14647 __input: &[u8],
14648 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14649 let avail_len = __input.len();
14650 let mut payload_buf = [0; Self::ENCODED_LEN];
14651 let mut buf = if avail_len < Self::ENCODED_LEN {
14652 payload_buf[0..avail_len].copy_from_slice(__input);
14653 Bytes::new(&payload_buf)
14654 } else {
14655 Bytes::new(__input)
14656 };
14657 let mut __struct = Self::default();
14658 let tmp = buf.get_u32_le()?;
14659 __struct.flags = GimbalManagerFlags::from_bits(tmp as <GimbalManagerFlags as Flags>::Bits)
14660 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
14661 flag_type: "GimbalManagerFlags",
14662 value: tmp as u64,
14663 })?;
14664 for v in &mut __struct.q {
14665 let val = buf.get_f32_le()?;
14666 *v = val;
14667 }
14668 __struct.angular_velocity_x = buf.get_f32_le()?;
14669 __struct.angular_velocity_y = buf.get_f32_le()?;
14670 __struct.angular_velocity_z = buf.get_f32_le()?;
14671 __struct.target_system = buf.get_u8()?;
14672 __struct.target_component = buf.get_u8()?;
14673 __struct.gimbal_device_id = buf.get_u8()?;
14674 Ok(__struct)
14675 }
14676 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14677 let mut __tmp = BytesMut::new(bytes);
14678 #[allow(clippy::absurd_extreme_comparisons)]
14679 #[allow(unused_comparisons)]
14680 if __tmp.remaining() < Self::ENCODED_LEN {
14681 panic!(
14682 "buffer is too small (need {} bytes, but got {})",
14683 Self::ENCODED_LEN,
14684 __tmp.remaining(),
14685 )
14686 }
14687 __tmp.put_u32_le(self.flags.bits() as u32);
14688 for val in &self.q {
14689 __tmp.put_f32_le(*val);
14690 }
14691 __tmp.put_f32_le(self.angular_velocity_x);
14692 __tmp.put_f32_le(self.angular_velocity_y);
14693 __tmp.put_f32_le(self.angular_velocity_z);
14694 __tmp.put_u8(self.target_system);
14695 __tmp.put_u8(self.target_component);
14696 __tmp.put_u8(self.gimbal_device_id);
14697 if matches!(version, MavlinkVersion::V2) {
14698 let len = __tmp.len();
14699 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14700 } else {
14701 __tmp.len()
14702 }
14703 }
14704}
14705#[doc = "High level message to control a gimbal manually. The angles or angular rates are unitless; the actual rates will depend on internal gimbal manager settings/configuration (e.g. set by parameters). This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case."]
14706#[doc = ""]
14707#[doc = "ID: 288"]
14708#[derive(Debug, Clone, PartialEq)]
14709#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14710#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14711#[cfg_attr(feature = "ts", derive(TS))]
14712#[cfg_attr(feature = "ts", ts(export))]
14713pub struct GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA {
14714 #[doc = "High level gimbal manager flags."]
14715 pub flags: GimbalManagerFlags,
14716 #[doc = "Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored)."]
14717 pub pitch: f32,
14718 #[doc = "Yaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored)."]
14719 pub yaw: f32,
14720 #[doc = "Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored)."]
14721 pub pitch_rate: f32,
14722 #[doc = "Yaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored)."]
14723 pub yaw_rate: f32,
14724 #[doc = "System ID"]
14725 pub target_system: u8,
14726 #[doc = "Component ID"]
14727 pub target_component: u8,
14728 #[doc = "Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals)."]
14729 pub gimbal_device_id: u8,
14730}
14731impl GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA {
14732 pub const ENCODED_LEN: usize = 23usize;
14733 pub const DEFAULT: Self = Self {
14734 flags: GimbalManagerFlags::DEFAULT,
14735 pitch: 0.0_f32,
14736 yaw: 0.0_f32,
14737 pitch_rate: 0.0_f32,
14738 yaw_rate: 0.0_f32,
14739 target_system: 0_u8,
14740 target_component: 0_u8,
14741 gimbal_device_id: 0_u8,
14742 };
14743 #[cfg(feature = "arbitrary")]
14744 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14745 use arbitrary::{Arbitrary, Unstructured};
14746 let mut buf = [0u8; 1024];
14747 rng.fill_bytes(&mut buf);
14748 let mut unstructured = Unstructured::new(&buf);
14749 Self::arbitrary(&mut unstructured).unwrap_or_default()
14750 }
14751}
14752impl Default for GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA {
14753 fn default() -> Self {
14754 Self::DEFAULT.clone()
14755 }
14756}
14757impl MessageData for GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA {
14758 type Message = MavMessage;
14759 const ID: u32 = 288u32;
14760 const NAME: &'static str = "GIMBAL_MANAGER_SET_MANUAL_CONTROL";
14761 const EXTRA_CRC: u8 = 20u8;
14762 const ENCODED_LEN: usize = 23usize;
14763 fn deser(
14764 _version: MavlinkVersion,
14765 __input: &[u8],
14766 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14767 let avail_len = __input.len();
14768 let mut payload_buf = [0; Self::ENCODED_LEN];
14769 let mut buf = if avail_len < Self::ENCODED_LEN {
14770 payload_buf[0..avail_len].copy_from_slice(__input);
14771 Bytes::new(&payload_buf)
14772 } else {
14773 Bytes::new(__input)
14774 };
14775 let mut __struct = Self::default();
14776 let tmp = buf.get_u32_le()?;
14777 __struct.flags = GimbalManagerFlags::from_bits(tmp as <GimbalManagerFlags as Flags>::Bits)
14778 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
14779 flag_type: "GimbalManagerFlags",
14780 value: tmp as u64,
14781 })?;
14782 __struct.pitch = buf.get_f32_le()?;
14783 __struct.yaw = buf.get_f32_le()?;
14784 __struct.pitch_rate = buf.get_f32_le()?;
14785 __struct.yaw_rate = buf.get_f32_le()?;
14786 __struct.target_system = buf.get_u8()?;
14787 __struct.target_component = buf.get_u8()?;
14788 __struct.gimbal_device_id = buf.get_u8()?;
14789 Ok(__struct)
14790 }
14791 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14792 let mut __tmp = BytesMut::new(bytes);
14793 #[allow(clippy::absurd_extreme_comparisons)]
14794 #[allow(unused_comparisons)]
14795 if __tmp.remaining() < Self::ENCODED_LEN {
14796 panic!(
14797 "buffer is too small (need {} bytes, but got {})",
14798 Self::ENCODED_LEN,
14799 __tmp.remaining(),
14800 )
14801 }
14802 __tmp.put_u32_le(self.flags.bits() as u32);
14803 __tmp.put_f32_le(self.pitch);
14804 __tmp.put_f32_le(self.yaw);
14805 __tmp.put_f32_le(self.pitch_rate);
14806 __tmp.put_f32_le(self.yaw_rate);
14807 __tmp.put_u8(self.target_system);
14808 __tmp.put_u8(self.target_component);
14809 __tmp.put_u8(self.gimbal_device_id);
14810 if matches!(version, MavlinkVersion::V2) {
14811 let len = __tmp.len();
14812 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14813 } else {
14814 __tmp.len()
14815 }
14816 }
14817}
14818#[doc = "Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation."]
14819#[doc = ""]
14820#[doc = "ID: 287"]
14821#[derive(Debug, Clone, PartialEq)]
14822#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14823#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14824#[cfg_attr(feature = "ts", derive(TS))]
14825#[cfg_attr(feature = "ts", ts(export))]
14826pub struct GIMBAL_MANAGER_SET_PITCHYAW_DATA {
14827 #[doc = "High level gimbal manager flags to use."]
14828 pub flags: GimbalManagerFlags,
14829 #[doc = "Pitch angle (positive: up, negative: down, NaN to be ignored)."]
14830 pub pitch: f32,
14831 #[doc = "Yaw angle (positive: to the right, negative: to the left, NaN to be ignored)."]
14832 pub yaw: f32,
14833 #[doc = "Pitch angular rate (positive: up, negative: down, NaN to be ignored)."]
14834 pub pitch_rate: f32,
14835 #[doc = "Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored)."]
14836 pub yaw_rate: f32,
14837 #[doc = "System ID"]
14838 pub target_system: u8,
14839 #[doc = "Component ID"]
14840 pub target_component: u8,
14841 #[doc = "Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals)."]
14842 pub gimbal_device_id: u8,
14843}
14844impl GIMBAL_MANAGER_SET_PITCHYAW_DATA {
14845 pub const ENCODED_LEN: usize = 23usize;
14846 pub const DEFAULT: Self = Self {
14847 flags: GimbalManagerFlags::DEFAULT,
14848 pitch: 0.0_f32,
14849 yaw: 0.0_f32,
14850 pitch_rate: 0.0_f32,
14851 yaw_rate: 0.0_f32,
14852 target_system: 0_u8,
14853 target_component: 0_u8,
14854 gimbal_device_id: 0_u8,
14855 };
14856 #[cfg(feature = "arbitrary")]
14857 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14858 use arbitrary::{Arbitrary, Unstructured};
14859 let mut buf = [0u8; 1024];
14860 rng.fill_bytes(&mut buf);
14861 let mut unstructured = Unstructured::new(&buf);
14862 Self::arbitrary(&mut unstructured).unwrap_or_default()
14863 }
14864}
14865impl Default for GIMBAL_MANAGER_SET_PITCHYAW_DATA {
14866 fn default() -> Self {
14867 Self::DEFAULT.clone()
14868 }
14869}
14870impl MessageData for GIMBAL_MANAGER_SET_PITCHYAW_DATA {
14871 type Message = MavMessage;
14872 const ID: u32 = 287u32;
14873 const NAME: &'static str = "GIMBAL_MANAGER_SET_PITCHYAW";
14874 const EXTRA_CRC: u8 = 1u8;
14875 const ENCODED_LEN: usize = 23usize;
14876 fn deser(
14877 _version: MavlinkVersion,
14878 __input: &[u8],
14879 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14880 let avail_len = __input.len();
14881 let mut payload_buf = [0; Self::ENCODED_LEN];
14882 let mut buf = if avail_len < Self::ENCODED_LEN {
14883 payload_buf[0..avail_len].copy_from_slice(__input);
14884 Bytes::new(&payload_buf)
14885 } else {
14886 Bytes::new(__input)
14887 };
14888 let mut __struct = Self::default();
14889 let tmp = buf.get_u32_le()?;
14890 __struct.flags = GimbalManagerFlags::from_bits(tmp as <GimbalManagerFlags as Flags>::Bits)
14891 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
14892 flag_type: "GimbalManagerFlags",
14893 value: tmp as u64,
14894 })?;
14895 __struct.pitch = buf.get_f32_le()?;
14896 __struct.yaw = buf.get_f32_le()?;
14897 __struct.pitch_rate = buf.get_f32_le()?;
14898 __struct.yaw_rate = buf.get_f32_le()?;
14899 __struct.target_system = buf.get_u8()?;
14900 __struct.target_component = buf.get_u8()?;
14901 __struct.gimbal_device_id = buf.get_u8()?;
14902 Ok(__struct)
14903 }
14904 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14905 let mut __tmp = BytesMut::new(bytes);
14906 #[allow(clippy::absurd_extreme_comparisons)]
14907 #[allow(unused_comparisons)]
14908 if __tmp.remaining() < Self::ENCODED_LEN {
14909 panic!(
14910 "buffer is too small (need {} bytes, but got {})",
14911 Self::ENCODED_LEN,
14912 __tmp.remaining(),
14913 )
14914 }
14915 __tmp.put_u32_le(self.flags.bits() as u32);
14916 __tmp.put_f32_le(self.pitch);
14917 __tmp.put_f32_le(self.yaw);
14918 __tmp.put_f32_le(self.pitch_rate);
14919 __tmp.put_f32_le(self.yaw_rate);
14920 __tmp.put_u8(self.target_system);
14921 __tmp.put_u8(self.target_component);
14922 __tmp.put_u8(self.gimbal_device_id);
14923 if matches!(version, MavlinkVersion::V2) {
14924 let len = __tmp.len();
14925 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14926 } else {
14927 __tmp.len()
14928 }
14929 }
14930}
14931#[doc = "Current status about a high level gimbal manager. This message should be broadcast at a low regular rate (e.g. 5Hz)."]
14932#[doc = ""]
14933#[doc = "ID: 281"]
14934#[derive(Debug, Clone, PartialEq)]
14935#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14936#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14937#[cfg_attr(feature = "ts", derive(TS))]
14938#[cfg_attr(feature = "ts", ts(export))]
14939pub struct GIMBAL_MANAGER_STATUS_DATA {
14940 #[doc = "Timestamp (time since system boot)."]
14941 pub time_boot_ms: u32,
14942 #[doc = "High level gimbal manager flags currently applied."]
14943 pub flags: GimbalManagerFlags,
14944 #[doc = "Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal)."]
14945 pub gimbal_device_id: u8,
14946 #[doc = "System ID of MAVLink component with primary control, 0 for none."]
14947 pub primary_control_sysid: u8,
14948 #[doc = "Component ID of MAVLink component with primary control, 0 for none."]
14949 pub primary_control_compid: u8,
14950 #[doc = "System ID of MAVLink component with secondary control, 0 for none."]
14951 pub secondary_control_sysid: u8,
14952 #[doc = "Component ID of MAVLink component with secondary control, 0 for none."]
14953 pub secondary_control_compid: u8,
14954}
14955impl GIMBAL_MANAGER_STATUS_DATA {
14956 pub const ENCODED_LEN: usize = 13usize;
14957 pub const DEFAULT: Self = Self {
14958 time_boot_ms: 0_u32,
14959 flags: GimbalManagerFlags::DEFAULT,
14960 gimbal_device_id: 0_u8,
14961 primary_control_sysid: 0_u8,
14962 primary_control_compid: 0_u8,
14963 secondary_control_sysid: 0_u8,
14964 secondary_control_compid: 0_u8,
14965 };
14966 #[cfg(feature = "arbitrary")]
14967 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14968 use arbitrary::{Arbitrary, Unstructured};
14969 let mut buf = [0u8; 1024];
14970 rng.fill_bytes(&mut buf);
14971 let mut unstructured = Unstructured::new(&buf);
14972 Self::arbitrary(&mut unstructured).unwrap_or_default()
14973 }
14974}
14975impl Default for GIMBAL_MANAGER_STATUS_DATA {
14976 fn default() -> Self {
14977 Self::DEFAULT.clone()
14978 }
14979}
14980impl MessageData for GIMBAL_MANAGER_STATUS_DATA {
14981 type Message = MavMessage;
14982 const ID: u32 = 281u32;
14983 const NAME: &'static str = "GIMBAL_MANAGER_STATUS";
14984 const EXTRA_CRC: u8 = 48u8;
14985 const ENCODED_LEN: usize = 13usize;
14986 fn deser(
14987 _version: MavlinkVersion,
14988 __input: &[u8],
14989 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14990 let avail_len = __input.len();
14991 let mut payload_buf = [0; Self::ENCODED_LEN];
14992 let mut buf = if avail_len < Self::ENCODED_LEN {
14993 payload_buf[0..avail_len].copy_from_slice(__input);
14994 Bytes::new(&payload_buf)
14995 } else {
14996 Bytes::new(__input)
14997 };
14998 let mut __struct = Self::default();
14999 __struct.time_boot_ms = buf.get_u32_le()?;
15000 let tmp = buf.get_u32_le()?;
15001 __struct.flags = GimbalManagerFlags::from_bits(tmp as <GimbalManagerFlags as Flags>::Bits)
15002 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
15003 flag_type: "GimbalManagerFlags",
15004 value: tmp as u64,
15005 })?;
15006 __struct.gimbal_device_id = buf.get_u8()?;
15007 __struct.primary_control_sysid = buf.get_u8()?;
15008 __struct.primary_control_compid = buf.get_u8()?;
15009 __struct.secondary_control_sysid = buf.get_u8()?;
15010 __struct.secondary_control_compid = buf.get_u8()?;
15011 Ok(__struct)
15012 }
15013 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15014 let mut __tmp = BytesMut::new(bytes);
15015 #[allow(clippy::absurd_extreme_comparisons)]
15016 #[allow(unused_comparisons)]
15017 if __tmp.remaining() < Self::ENCODED_LEN {
15018 panic!(
15019 "buffer is too small (need {} bytes, but got {})",
15020 Self::ENCODED_LEN,
15021 __tmp.remaining(),
15022 )
15023 }
15024 __tmp.put_u32_le(self.time_boot_ms);
15025 __tmp.put_u32_le(self.flags.bits() as u32);
15026 __tmp.put_u8(self.gimbal_device_id);
15027 __tmp.put_u8(self.primary_control_sysid);
15028 __tmp.put_u8(self.primary_control_compid);
15029 __tmp.put_u8(self.secondary_control_sysid);
15030 __tmp.put_u8(self.secondary_control_compid);
15031 if matches!(version, MavlinkVersion::V2) {
15032 let len = __tmp.len();
15033 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15034 } else {
15035 __tmp.len()
15036 }
15037 }
15038}
15039#[doc = "The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient."]
15040#[doc = ""]
15041#[doc = "ID: 33"]
15042#[derive(Debug, Clone, PartialEq)]
15043#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15044#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15045#[cfg_attr(feature = "ts", derive(TS))]
15046#[cfg_attr(feature = "ts", ts(export))]
15047pub struct GLOBAL_POSITION_INT_DATA {
15048 #[doc = "Timestamp (time since system boot)."]
15049 pub time_boot_ms: u32,
15050 #[doc = "Latitude, expressed"]
15051 pub lat: i32,
15052 #[doc = "Longitude, expressed"]
15053 pub lon: i32,
15054 #[doc = "Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL."]
15055 pub alt: i32,
15056 #[doc = "Altitude above home"]
15057 pub relative_alt: i32,
15058 #[doc = "Ground X Speed (Latitude, positive north)"]
15059 pub vx: i16,
15060 #[doc = "Ground Y Speed (Longitude, positive east)"]
15061 pub vy: i16,
15062 #[doc = "Ground Z Speed (Altitude, positive down)"]
15063 pub vz: i16,
15064 #[doc = "Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX"]
15065 pub hdg: u16,
15066}
15067impl GLOBAL_POSITION_INT_DATA {
15068 pub const ENCODED_LEN: usize = 28usize;
15069 pub const DEFAULT: Self = Self {
15070 time_boot_ms: 0_u32,
15071 lat: 0_i32,
15072 lon: 0_i32,
15073 alt: 0_i32,
15074 relative_alt: 0_i32,
15075 vx: 0_i16,
15076 vy: 0_i16,
15077 vz: 0_i16,
15078 hdg: 0_u16,
15079 };
15080 #[cfg(feature = "arbitrary")]
15081 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15082 use arbitrary::{Arbitrary, Unstructured};
15083 let mut buf = [0u8; 1024];
15084 rng.fill_bytes(&mut buf);
15085 let mut unstructured = Unstructured::new(&buf);
15086 Self::arbitrary(&mut unstructured).unwrap_or_default()
15087 }
15088}
15089impl Default for GLOBAL_POSITION_INT_DATA {
15090 fn default() -> Self {
15091 Self::DEFAULT.clone()
15092 }
15093}
15094impl MessageData for GLOBAL_POSITION_INT_DATA {
15095 type Message = MavMessage;
15096 const ID: u32 = 33u32;
15097 const NAME: &'static str = "GLOBAL_POSITION_INT";
15098 const EXTRA_CRC: u8 = 104u8;
15099 const ENCODED_LEN: usize = 28usize;
15100 fn deser(
15101 _version: MavlinkVersion,
15102 __input: &[u8],
15103 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15104 let avail_len = __input.len();
15105 let mut payload_buf = [0; Self::ENCODED_LEN];
15106 let mut buf = if avail_len < Self::ENCODED_LEN {
15107 payload_buf[0..avail_len].copy_from_slice(__input);
15108 Bytes::new(&payload_buf)
15109 } else {
15110 Bytes::new(__input)
15111 };
15112 let mut __struct = Self::default();
15113 __struct.time_boot_ms = buf.get_u32_le()?;
15114 __struct.lat = buf.get_i32_le()?;
15115 __struct.lon = buf.get_i32_le()?;
15116 __struct.alt = buf.get_i32_le()?;
15117 __struct.relative_alt = buf.get_i32_le()?;
15118 __struct.vx = buf.get_i16_le()?;
15119 __struct.vy = buf.get_i16_le()?;
15120 __struct.vz = buf.get_i16_le()?;
15121 __struct.hdg = buf.get_u16_le()?;
15122 Ok(__struct)
15123 }
15124 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15125 let mut __tmp = BytesMut::new(bytes);
15126 #[allow(clippy::absurd_extreme_comparisons)]
15127 #[allow(unused_comparisons)]
15128 if __tmp.remaining() < Self::ENCODED_LEN {
15129 panic!(
15130 "buffer is too small (need {} bytes, but got {})",
15131 Self::ENCODED_LEN,
15132 __tmp.remaining(),
15133 )
15134 }
15135 __tmp.put_u32_le(self.time_boot_ms);
15136 __tmp.put_i32_le(self.lat);
15137 __tmp.put_i32_le(self.lon);
15138 __tmp.put_i32_le(self.alt);
15139 __tmp.put_i32_le(self.relative_alt);
15140 __tmp.put_i16_le(self.vx);
15141 __tmp.put_i16_le(self.vy);
15142 __tmp.put_i16_le(self.vz);
15143 __tmp.put_u16_le(self.hdg);
15144 if matches!(version, MavlinkVersion::V2) {
15145 let len = __tmp.len();
15146 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15147 } else {
15148 __tmp.len()
15149 }
15150 }
15151}
15152#[doc = "The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient. NOTE: This message is intended for onboard networks / companion computers and higher-bandwidth links and optimized for accuracy and completeness. Please use the GLOBAL_POSITION_INT message for a minimal subset."]
15153#[doc = ""]
15154#[doc = "ID: 63"]
15155#[derive(Debug, Clone, PartialEq)]
15156#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15157#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15158#[cfg_attr(feature = "ts", derive(TS))]
15159#[cfg_attr(feature = "ts", ts(export))]
15160pub struct GLOBAL_POSITION_INT_COV_DATA {
15161 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
15162 pub time_usec: u64,
15163 #[doc = "Latitude"]
15164 pub lat: i32,
15165 #[doc = "Longitude"]
15166 pub lon: i32,
15167 #[doc = "Altitude in meters above MSL"]
15168 pub alt: i32,
15169 #[doc = "Altitude above ground"]
15170 pub relative_alt: i32,
15171 #[doc = "Ground X Speed (Latitude)"]
15172 pub vx: f32,
15173 #[doc = "Ground Y Speed (Longitude)"]
15174 pub vy: f32,
15175 #[doc = "Ground Z Speed (Altitude)"]
15176 pub vz: f32,
15177 #[doc = "Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array."]
15178 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15179 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
15180 pub covariance: [f32; 36],
15181 #[doc = "Class id of the estimator this estimate originated from."]
15182 pub estimator_type: MavEstimatorType,
15183}
15184impl GLOBAL_POSITION_INT_COV_DATA {
15185 pub const ENCODED_LEN: usize = 181usize;
15186 pub const DEFAULT: Self = Self {
15187 time_usec: 0_u64,
15188 lat: 0_i32,
15189 lon: 0_i32,
15190 alt: 0_i32,
15191 relative_alt: 0_i32,
15192 vx: 0.0_f32,
15193 vy: 0.0_f32,
15194 vz: 0.0_f32,
15195 covariance: [0.0_f32; 36usize],
15196 estimator_type: MavEstimatorType::DEFAULT,
15197 };
15198 #[cfg(feature = "arbitrary")]
15199 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15200 use arbitrary::{Arbitrary, Unstructured};
15201 let mut buf = [0u8; 1024];
15202 rng.fill_bytes(&mut buf);
15203 let mut unstructured = Unstructured::new(&buf);
15204 Self::arbitrary(&mut unstructured).unwrap_or_default()
15205 }
15206}
15207impl Default for GLOBAL_POSITION_INT_COV_DATA {
15208 fn default() -> Self {
15209 Self::DEFAULT.clone()
15210 }
15211}
15212impl MessageData for GLOBAL_POSITION_INT_COV_DATA {
15213 type Message = MavMessage;
15214 const ID: u32 = 63u32;
15215 const NAME: &'static str = "GLOBAL_POSITION_INT_COV";
15216 const EXTRA_CRC: u8 = 119u8;
15217 const ENCODED_LEN: usize = 181usize;
15218 fn deser(
15219 _version: MavlinkVersion,
15220 __input: &[u8],
15221 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15222 let avail_len = __input.len();
15223 let mut payload_buf = [0; Self::ENCODED_LEN];
15224 let mut buf = if avail_len < Self::ENCODED_LEN {
15225 payload_buf[0..avail_len].copy_from_slice(__input);
15226 Bytes::new(&payload_buf)
15227 } else {
15228 Bytes::new(__input)
15229 };
15230 let mut __struct = Self::default();
15231 __struct.time_usec = buf.get_u64_le()?;
15232 __struct.lat = buf.get_i32_le()?;
15233 __struct.lon = buf.get_i32_le()?;
15234 __struct.alt = buf.get_i32_le()?;
15235 __struct.relative_alt = buf.get_i32_le()?;
15236 __struct.vx = buf.get_f32_le()?;
15237 __struct.vy = buf.get_f32_le()?;
15238 __struct.vz = buf.get_f32_le()?;
15239 for v in &mut __struct.covariance {
15240 let val = buf.get_f32_le()?;
15241 *v = val;
15242 }
15243 let tmp = buf.get_u8()?;
15244 __struct.estimator_type =
15245 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
15246 enum_type: "MavEstimatorType",
15247 value: tmp as u64,
15248 })?;
15249 Ok(__struct)
15250 }
15251 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15252 let mut __tmp = BytesMut::new(bytes);
15253 #[allow(clippy::absurd_extreme_comparisons)]
15254 #[allow(unused_comparisons)]
15255 if __tmp.remaining() < Self::ENCODED_LEN {
15256 panic!(
15257 "buffer is too small (need {} bytes, but got {})",
15258 Self::ENCODED_LEN,
15259 __tmp.remaining(),
15260 )
15261 }
15262 __tmp.put_u64_le(self.time_usec);
15263 __tmp.put_i32_le(self.lat);
15264 __tmp.put_i32_le(self.lon);
15265 __tmp.put_i32_le(self.alt);
15266 __tmp.put_i32_le(self.relative_alt);
15267 __tmp.put_f32_le(self.vx);
15268 __tmp.put_f32_le(self.vy);
15269 __tmp.put_f32_le(self.vz);
15270 for val in &self.covariance {
15271 __tmp.put_f32_le(*val);
15272 }
15273 __tmp.put_u8(self.estimator_type as u8);
15274 if matches!(version, MavlinkVersion::V2) {
15275 let len = __tmp.len();
15276 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15277 } else {
15278 __tmp.len()
15279 }
15280 }
15281}
15282#[doc = "Global position/attitude estimate from a vision source."]
15283#[doc = ""]
15284#[doc = "ID: 101"]
15285#[derive(Debug, Clone, PartialEq)]
15286#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15287#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15288#[cfg_attr(feature = "ts", derive(TS))]
15289#[cfg_attr(feature = "ts", ts(export))]
15290pub struct GLOBAL_VISION_POSITION_ESTIMATE_DATA {
15291 #[doc = "Timestamp (UNIX time or since system boot)"]
15292 pub usec: u64,
15293 #[doc = "Global X position"]
15294 pub x: f32,
15295 #[doc = "Global Y position"]
15296 pub y: f32,
15297 #[doc = "Global Z position"]
15298 pub z: f32,
15299 #[doc = "Roll angle"]
15300 pub roll: f32,
15301 #[doc = "Pitch angle"]
15302 pub pitch: f32,
15303 #[doc = "Yaw angle"]
15304 pub yaw: f32,
15305 #[doc = "Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x_global, y_global, z_global, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
15306 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
15307 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15308 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
15309 pub covariance: [f32; 21],
15310 #[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps."]
15311 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
15312 pub reset_counter: u8,
15313}
15314impl GLOBAL_VISION_POSITION_ESTIMATE_DATA {
15315 pub const ENCODED_LEN: usize = 117usize;
15316 pub const DEFAULT: Self = Self {
15317 usec: 0_u64,
15318 x: 0.0_f32,
15319 y: 0.0_f32,
15320 z: 0.0_f32,
15321 roll: 0.0_f32,
15322 pitch: 0.0_f32,
15323 yaw: 0.0_f32,
15324 covariance: [0.0_f32; 21usize],
15325 reset_counter: 0_u8,
15326 };
15327 #[cfg(feature = "arbitrary")]
15328 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15329 use arbitrary::{Arbitrary, Unstructured};
15330 let mut buf = [0u8; 1024];
15331 rng.fill_bytes(&mut buf);
15332 let mut unstructured = Unstructured::new(&buf);
15333 Self::arbitrary(&mut unstructured).unwrap_or_default()
15334 }
15335}
15336impl Default for GLOBAL_VISION_POSITION_ESTIMATE_DATA {
15337 fn default() -> Self {
15338 Self::DEFAULT.clone()
15339 }
15340}
15341impl MessageData for GLOBAL_VISION_POSITION_ESTIMATE_DATA {
15342 type Message = MavMessage;
15343 const ID: u32 = 101u32;
15344 const NAME: &'static str = "GLOBAL_VISION_POSITION_ESTIMATE";
15345 const EXTRA_CRC: u8 = 102u8;
15346 const ENCODED_LEN: usize = 117usize;
15347 fn deser(
15348 _version: MavlinkVersion,
15349 __input: &[u8],
15350 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15351 let avail_len = __input.len();
15352 let mut payload_buf = [0; Self::ENCODED_LEN];
15353 let mut buf = if avail_len < Self::ENCODED_LEN {
15354 payload_buf[0..avail_len].copy_from_slice(__input);
15355 Bytes::new(&payload_buf)
15356 } else {
15357 Bytes::new(__input)
15358 };
15359 let mut __struct = Self::default();
15360 __struct.usec = buf.get_u64_le()?;
15361 __struct.x = buf.get_f32_le()?;
15362 __struct.y = buf.get_f32_le()?;
15363 __struct.z = buf.get_f32_le()?;
15364 __struct.roll = buf.get_f32_le()?;
15365 __struct.pitch = buf.get_f32_le()?;
15366 __struct.yaw = buf.get_f32_le()?;
15367 for v in &mut __struct.covariance {
15368 let val = buf.get_f32_le()?;
15369 *v = val;
15370 }
15371 __struct.reset_counter = buf.get_u8()?;
15372 Ok(__struct)
15373 }
15374 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15375 let mut __tmp = BytesMut::new(bytes);
15376 #[allow(clippy::absurd_extreme_comparisons)]
15377 #[allow(unused_comparisons)]
15378 if __tmp.remaining() < Self::ENCODED_LEN {
15379 panic!(
15380 "buffer is too small (need {} bytes, but got {})",
15381 Self::ENCODED_LEN,
15382 __tmp.remaining(),
15383 )
15384 }
15385 __tmp.put_u64_le(self.usec);
15386 __tmp.put_f32_le(self.x);
15387 __tmp.put_f32_le(self.y);
15388 __tmp.put_f32_le(self.z);
15389 __tmp.put_f32_le(self.roll);
15390 __tmp.put_f32_le(self.pitch);
15391 __tmp.put_f32_le(self.yaw);
15392 if matches!(version, MavlinkVersion::V2) {
15393 for val in &self.covariance {
15394 __tmp.put_f32_le(*val);
15395 }
15396 __tmp.put_u8(self.reset_counter);
15397 let len = __tmp.len();
15398 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15399 } else {
15400 __tmp.len()
15401 }
15402 }
15403}
15404#[doc = "Second GPS data."]
15405#[doc = ""]
15406#[doc = "ID: 124"]
15407#[derive(Debug, Clone, PartialEq)]
15408#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15409#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15410#[cfg_attr(feature = "ts", derive(TS))]
15411#[cfg_attr(feature = "ts", ts(export))]
15412pub struct GPS2_RAW_DATA {
15413 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
15414 pub time_usec: u64,
15415 #[doc = "Latitude (WGS84)"]
15416 pub lat: i32,
15417 #[doc = "Longitude (WGS84)"]
15418 pub lon: i32,
15419 #[doc = "Altitude (MSL). Positive for up."]
15420 pub alt: i32,
15421 #[doc = "Age of DGPS info"]
15422 pub dgps_age: u32,
15423 #[doc = "GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
15424 pub eph: u16,
15425 #[doc = "GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
15426 pub epv: u16,
15427 #[doc = "GPS ground speed. If unknown, set to: UINT16_MAX"]
15428 pub vel: u16,
15429 #[doc = "Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX"]
15430 pub cog: u16,
15431 #[doc = "GPS fix type."]
15432 pub fix_type: GpsFixType,
15433 #[doc = "Number of satellites visible. If unknown, set to UINT8_MAX"]
15434 pub satellites_visible: u8,
15435 #[doc = "Number of DGPS satellites"]
15436 pub dgps_numch: u8,
15437 #[doc = "Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north."]
15438 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
15439 pub yaw: u16,
15440 #[doc = "Altitude (above WGS84, EGM96 ellipsoid). Positive for up."]
15441 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
15442 pub alt_ellipsoid: i32,
15443 #[doc = "Position uncertainty."]
15444 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
15445 pub h_acc: u32,
15446 #[doc = "Altitude uncertainty."]
15447 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
15448 pub v_acc: u32,
15449 #[doc = "Speed uncertainty."]
15450 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
15451 pub vel_acc: u32,
15452 #[doc = "Heading / track uncertainty"]
15453 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
15454 pub hdg_acc: u32,
15455}
15456impl GPS2_RAW_DATA {
15457 pub const ENCODED_LEN: usize = 57usize;
15458 pub const DEFAULT: Self = Self {
15459 time_usec: 0_u64,
15460 lat: 0_i32,
15461 lon: 0_i32,
15462 alt: 0_i32,
15463 dgps_age: 0_u32,
15464 eph: 0_u16,
15465 epv: 0_u16,
15466 vel: 0_u16,
15467 cog: 0_u16,
15468 fix_type: GpsFixType::DEFAULT,
15469 satellites_visible: 0_u8,
15470 dgps_numch: 0_u8,
15471 yaw: 0_u16,
15472 alt_ellipsoid: 0_i32,
15473 h_acc: 0_u32,
15474 v_acc: 0_u32,
15475 vel_acc: 0_u32,
15476 hdg_acc: 0_u32,
15477 };
15478 #[cfg(feature = "arbitrary")]
15479 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15480 use arbitrary::{Arbitrary, Unstructured};
15481 let mut buf = [0u8; 1024];
15482 rng.fill_bytes(&mut buf);
15483 let mut unstructured = Unstructured::new(&buf);
15484 Self::arbitrary(&mut unstructured).unwrap_or_default()
15485 }
15486}
15487impl Default for GPS2_RAW_DATA {
15488 fn default() -> Self {
15489 Self::DEFAULT.clone()
15490 }
15491}
15492impl MessageData for GPS2_RAW_DATA {
15493 type Message = MavMessage;
15494 const ID: u32 = 124u32;
15495 const NAME: &'static str = "GPS2_RAW";
15496 const EXTRA_CRC: u8 = 87u8;
15497 const ENCODED_LEN: usize = 57usize;
15498 fn deser(
15499 _version: MavlinkVersion,
15500 __input: &[u8],
15501 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15502 let avail_len = __input.len();
15503 let mut payload_buf = [0; Self::ENCODED_LEN];
15504 let mut buf = if avail_len < Self::ENCODED_LEN {
15505 payload_buf[0..avail_len].copy_from_slice(__input);
15506 Bytes::new(&payload_buf)
15507 } else {
15508 Bytes::new(__input)
15509 };
15510 let mut __struct = Self::default();
15511 __struct.time_usec = buf.get_u64_le()?;
15512 __struct.lat = buf.get_i32_le()?;
15513 __struct.lon = buf.get_i32_le()?;
15514 __struct.alt = buf.get_i32_le()?;
15515 __struct.dgps_age = buf.get_u32_le()?;
15516 __struct.eph = buf.get_u16_le()?;
15517 __struct.epv = buf.get_u16_le()?;
15518 __struct.vel = buf.get_u16_le()?;
15519 __struct.cog = buf.get_u16_le()?;
15520 let tmp = buf.get_u8()?;
15521 __struct.fix_type =
15522 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
15523 enum_type: "GpsFixType",
15524 value: tmp as u64,
15525 })?;
15526 __struct.satellites_visible = buf.get_u8()?;
15527 __struct.dgps_numch = buf.get_u8()?;
15528 __struct.yaw = buf.get_u16_le()?;
15529 __struct.alt_ellipsoid = buf.get_i32_le()?;
15530 __struct.h_acc = buf.get_u32_le()?;
15531 __struct.v_acc = buf.get_u32_le()?;
15532 __struct.vel_acc = buf.get_u32_le()?;
15533 __struct.hdg_acc = buf.get_u32_le()?;
15534 Ok(__struct)
15535 }
15536 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15537 let mut __tmp = BytesMut::new(bytes);
15538 #[allow(clippy::absurd_extreme_comparisons)]
15539 #[allow(unused_comparisons)]
15540 if __tmp.remaining() < Self::ENCODED_LEN {
15541 panic!(
15542 "buffer is too small (need {} bytes, but got {})",
15543 Self::ENCODED_LEN,
15544 __tmp.remaining(),
15545 )
15546 }
15547 __tmp.put_u64_le(self.time_usec);
15548 __tmp.put_i32_le(self.lat);
15549 __tmp.put_i32_le(self.lon);
15550 __tmp.put_i32_le(self.alt);
15551 __tmp.put_u32_le(self.dgps_age);
15552 __tmp.put_u16_le(self.eph);
15553 __tmp.put_u16_le(self.epv);
15554 __tmp.put_u16_le(self.vel);
15555 __tmp.put_u16_le(self.cog);
15556 __tmp.put_u8(self.fix_type as u8);
15557 __tmp.put_u8(self.satellites_visible);
15558 __tmp.put_u8(self.dgps_numch);
15559 if matches!(version, MavlinkVersion::V2) {
15560 __tmp.put_u16_le(self.yaw);
15561 __tmp.put_i32_le(self.alt_ellipsoid);
15562 __tmp.put_u32_le(self.h_acc);
15563 __tmp.put_u32_le(self.v_acc);
15564 __tmp.put_u32_le(self.vel_acc);
15565 __tmp.put_u32_le(self.hdg_acc);
15566 let len = __tmp.len();
15567 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15568 } else {
15569 __tmp.len()
15570 }
15571 }
15572}
15573#[doc = "RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting."]
15574#[doc = ""]
15575#[doc = "ID: 128"]
15576#[derive(Debug, Clone, PartialEq)]
15577#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15578#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15579#[cfg_attr(feature = "ts", derive(TS))]
15580#[cfg_attr(feature = "ts", ts(export))]
15581pub struct GPS2_RTK_DATA {
15582 #[doc = "Time since boot of last baseline message received."]
15583 pub time_last_baseline_ms: u32,
15584 #[doc = "GPS Time of Week of last baseline"]
15585 pub tow: u32,
15586 #[doc = "Current baseline in ECEF x or NED north component."]
15587 pub baseline_a_mm: i32,
15588 #[doc = "Current baseline in ECEF y or NED east component."]
15589 pub baseline_b_mm: i32,
15590 #[doc = "Current baseline in ECEF z or NED down component."]
15591 pub baseline_c_mm: i32,
15592 #[doc = "Current estimate of baseline accuracy."]
15593 pub accuracy: u32,
15594 #[doc = "Current number of integer ambiguity hypotheses."]
15595 pub iar_num_hypotheses: i32,
15596 #[doc = "GPS Week Number of last baseline"]
15597 pub wn: u16,
15598 #[doc = "Identification of connected RTK receiver."]
15599 pub rtk_receiver_id: u8,
15600 #[doc = "GPS-specific health report for RTK data."]
15601 pub rtk_health: u8,
15602 #[doc = "Rate of baseline messages being received by GPS"]
15603 pub rtk_rate: u8,
15604 #[doc = "Current number of sats used for RTK calculation."]
15605 pub nsats: u8,
15606 #[doc = "Coordinate system of baseline"]
15607 pub baseline_coords_type: RtkBaselineCoordinateSystem,
15608}
15609impl GPS2_RTK_DATA {
15610 pub const ENCODED_LEN: usize = 35usize;
15611 pub const DEFAULT: Self = Self {
15612 time_last_baseline_ms: 0_u32,
15613 tow: 0_u32,
15614 baseline_a_mm: 0_i32,
15615 baseline_b_mm: 0_i32,
15616 baseline_c_mm: 0_i32,
15617 accuracy: 0_u32,
15618 iar_num_hypotheses: 0_i32,
15619 wn: 0_u16,
15620 rtk_receiver_id: 0_u8,
15621 rtk_health: 0_u8,
15622 rtk_rate: 0_u8,
15623 nsats: 0_u8,
15624 baseline_coords_type: RtkBaselineCoordinateSystem::DEFAULT,
15625 };
15626 #[cfg(feature = "arbitrary")]
15627 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15628 use arbitrary::{Arbitrary, Unstructured};
15629 let mut buf = [0u8; 1024];
15630 rng.fill_bytes(&mut buf);
15631 let mut unstructured = Unstructured::new(&buf);
15632 Self::arbitrary(&mut unstructured).unwrap_or_default()
15633 }
15634}
15635impl Default for GPS2_RTK_DATA {
15636 fn default() -> Self {
15637 Self::DEFAULT.clone()
15638 }
15639}
15640impl MessageData for GPS2_RTK_DATA {
15641 type Message = MavMessage;
15642 const ID: u32 = 128u32;
15643 const NAME: &'static str = "GPS2_RTK";
15644 const EXTRA_CRC: u8 = 226u8;
15645 const ENCODED_LEN: usize = 35usize;
15646 fn deser(
15647 _version: MavlinkVersion,
15648 __input: &[u8],
15649 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15650 let avail_len = __input.len();
15651 let mut payload_buf = [0; Self::ENCODED_LEN];
15652 let mut buf = if avail_len < Self::ENCODED_LEN {
15653 payload_buf[0..avail_len].copy_from_slice(__input);
15654 Bytes::new(&payload_buf)
15655 } else {
15656 Bytes::new(__input)
15657 };
15658 let mut __struct = Self::default();
15659 __struct.time_last_baseline_ms = buf.get_u32_le()?;
15660 __struct.tow = buf.get_u32_le()?;
15661 __struct.baseline_a_mm = buf.get_i32_le()?;
15662 __struct.baseline_b_mm = buf.get_i32_le()?;
15663 __struct.baseline_c_mm = buf.get_i32_le()?;
15664 __struct.accuracy = buf.get_u32_le()?;
15665 __struct.iar_num_hypotheses = buf.get_i32_le()?;
15666 __struct.wn = buf.get_u16_le()?;
15667 __struct.rtk_receiver_id = buf.get_u8()?;
15668 __struct.rtk_health = buf.get_u8()?;
15669 __struct.rtk_rate = buf.get_u8()?;
15670 __struct.nsats = buf.get_u8()?;
15671 let tmp = buf.get_u8()?;
15672 __struct.baseline_coords_type =
15673 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
15674 enum_type: "RtkBaselineCoordinateSystem",
15675 value: tmp as u64,
15676 })?;
15677 Ok(__struct)
15678 }
15679 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15680 let mut __tmp = BytesMut::new(bytes);
15681 #[allow(clippy::absurd_extreme_comparisons)]
15682 #[allow(unused_comparisons)]
15683 if __tmp.remaining() < Self::ENCODED_LEN {
15684 panic!(
15685 "buffer is too small (need {} bytes, but got {})",
15686 Self::ENCODED_LEN,
15687 __tmp.remaining(),
15688 )
15689 }
15690 __tmp.put_u32_le(self.time_last_baseline_ms);
15691 __tmp.put_u32_le(self.tow);
15692 __tmp.put_i32_le(self.baseline_a_mm);
15693 __tmp.put_i32_le(self.baseline_b_mm);
15694 __tmp.put_i32_le(self.baseline_c_mm);
15695 __tmp.put_u32_le(self.accuracy);
15696 __tmp.put_i32_le(self.iar_num_hypotheses);
15697 __tmp.put_u16_le(self.wn);
15698 __tmp.put_u8(self.rtk_receiver_id);
15699 __tmp.put_u8(self.rtk_health);
15700 __tmp.put_u8(self.rtk_rate);
15701 __tmp.put_u8(self.nsats);
15702 __tmp.put_u8(self.baseline_coords_type as u8);
15703 if matches!(version, MavlinkVersion::V2) {
15704 let len = __tmp.len();
15705 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15706 } else {
15707 __tmp.len()
15708 }
15709 }
15710}
15711#[doc = "Publishes the GPS coordinates of the vehicle local origin (0,0,0) position. Emitted whenever a new GPS-Local position mapping is requested or set - e.g. following SET_GPS_GLOBAL_ORIGIN message."]
15712#[doc = ""]
15713#[doc = "ID: 49"]
15714#[derive(Debug, Clone, PartialEq)]
15715#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15716#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15717#[cfg_attr(feature = "ts", derive(TS))]
15718#[cfg_attr(feature = "ts", ts(export))]
15719pub struct GPS_GLOBAL_ORIGIN_DATA {
15720 #[doc = "Latitude (WGS84)"]
15721 pub latitude: i32,
15722 #[doc = "Longitude (WGS84)"]
15723 pub longitude: i32,
15724 #[doc = "Altitude (MSL). Positive for up."]
15725 pub altitude: i32,
15726 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
15727 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
15728 pub time_usec: u64,
15729}
15730impl GPS_GLOBAL_ORIGIN_DATA {
15731 pub const ENCODED_LEN: usize = 20usize;
15732 pub const DEFAULT: Self = Self {
15733 latitude: 0_i32,
15734 longitude: 0_i32,
15735 altitude: 0_i32,
15736 time_usec: 0_u64,
15737 };
15738 #[cfg(feature = "arbitrary")]
15739 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15740 use arbitrary::{Arbitrary, Unstructured};
15741 let mut buf = [0u8; 1024];
15742 rng.fill_bytes(&mut buf);
15743 let mut unstructured = Unstructured::new(&buf);
15744 Self::arbitrary(&mut unstructured).unwrap_or_default()
15745 }
15746}
15747impl Default for GPS_GLOBAL_ORIGIN_DATA {
15748 fn default() -> Self {
15749 Self::DEFAULT.clone()
15750 }
15751}
15752impl MessageData for GPS_GLOBAL_ORIGIN_DATA {
15753 type Message = MavMessage;
15754 const ID: u32 = 49u32;
15755 const NAME: &'static str = "GPS_GLOBAL_ORIGIN";
15756 const EXTRA_CRC: u8 = 39u8;
15757 const ENCODED_LEN: usize = 20usize;
15758 fn deser(
15759 _version: MavlinkVersion,
15760 __input: &[u8],
15761 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15762 let avail_len = __input.len();
15763 let mut payload_buf = [0; Self::ENCODED_LEN];
15764 let mut buf = if avail_len < Self::ENCODED_LEN {
15765 payload_buf[0..avail_len].copy_from_slice(__input);
15766 Bytes::new(&payload_buf)
15767 } else {
15768 Bytes::new(__input)
15769 };
15770 let mut __struct = Self::default();
15771 __struct.latitude = buf.get_i32_le()?;
15772 __struct.longitude = buf.get_i32_le()?;
15773 __struct.altitude = buf.get_i32_le()?;
15774 __struct.time_usec = buf.get_u64_le()?;
15775 Ok(__struct)
15776 }
15777 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15778 let mut __tmp = BytesMut::new(bytes);
15779 #[allow(clippy::absurd_extreme_comparisons)]
15780 #[allow(unused_comparisons)]
15781 if __tmp.remaining() < Self::ENCODED_LEN {
15782 panic!(
15783 "buffer is too small (need {} bytes, but got {})",
15784 Self::ENCODED_LEN,
15785 __tmp.remaining(),
15786 )
15787 }
15788 __tmp.put_i32_le(self.latitude);
15789 __tmp.put_i32_le(self.longitude);
15790 __tmp.put_i32_le(self.altitude);
15791 if matches!(version, MavlinkVersion::V2) {
15792 __tmp.put_u64_le(self.time_usec);
15793 let len = __tmp.len();
15794 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15795 } else {
15796 __tmp.len()
15797 }
15798 }
15799}
15800#[deprecated = " See `GPS_RTCM_DATA` (Deprecated since 2022-05)"]
15801#[doc = "Data for injecting into the onboard GPS (used for DGPS)."]
15802#[doc = ""]
15803#[doc = "ID: 123"]
15804#[derive(Debug, Clone, PartialEq)]
15805#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15806#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15807#[cfg_attr(feature = "ts", derive(TS))]
15808#[cfg_attr(feature = "ts", ts(export))]
15809pub struct GPS_INJECT_DATA_DATA {
15810 #[doc = "System ID"]
15811 pub target_system: u8,
15812 #[doc = "Component ID"]
15813 pub target_component: u8,
15814 #[doc = "Data length"]
15815 pub len: u8,
15816 #[doc = "Raw data (110 is enough for 12 satellites of RTCMv2)"]
15817 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15818 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
15819 pub data: [u8; 110],
15820}
15821impl GPS_INJECT_DATA_DATA {
15822 pub const ENCODED_LEN: usize = 113usize;
15823 pub const DEFAULT: Self = Self {
15824 target_system: 0_u8,
15825 target_component: 0_u8,
15826 len: 0_u8,
15827 data: [0_u8; 110usize],
15828 };
15829 #[cfg(feature = "arbitrary")]
15830 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15831 use arbitrary::{Arbitrary, Unstructured};
15832 let mut buf = [0u8; 1024];
15833 rng.fill_bytes(&mut buf);
15834 let mut unstructured = Unstructured::new(&buf);
15835 Self::arbitrary(&mut unstructured).unwrap_or_default()
15836 }
15837}
15838impl Default for GPS_INJECT_DATA_DATA {
15839 fn default() -> Self {
15840 Self::DEFAULT.clone()
15841 }
15842}
15843impl MessageData for GPS_INJECT_DATA_DATA {
15844 type Message = MavMessage;
15845 const ID: u32 = 123u32;
15846 const NAME: &'static str = "GPS_INJECT_DATA";
15847 const EXTRA_CRC: u8 = 250u8;
15848 const ENCODED_LEN: usize = 113usize;
15849 fn deser(
15850 _version: MavlinkVersion,
15851 __input: &[u8],
15852 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15853 let avail_len = __input.len();
15854 let mut payload_buf = [0; Self::ENCODED_LEN];
15855 let mut buf = if avail_len < Self::ENCODED_LEN {
15856 payload_buf[0..avail_len].copy_from_slice(__input);
15857 Bytes::new(&payload_buf)
15858 } else {
15859 Bytes::new(__input)
15860 };
15861 let mut __struct = Self::default();
15862 __struct.target_system = buf.get_u8()?;
15863 __struct.target_component = buf.get_u8()?;
15864 __struct.len = buf.get_u8()?;
15865 for v in &mut __struct.data {
15866 let val = buf.get_u8()?;
15867 *v = val;
15868 }
15869 Ok(__struct)
15870 }
15871 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15872 let mut __tmp = BytesMut::new(bytes);
15873 #[allow(clippy::absurd_extreme_comparisons)]
15874 #[allow(unused_comparisons)]
15875 if __tmp.remaining() < Self::ENCODED_LEN {
15876 panic!(
15877 "buffer is too small (need {} bytes, but got {})",
15878 Self::ENCODED_LEN,
15879 __tmp.remaining(),
15880 )
15881 }
15882 __tmp.put_u8(self.target_system);
15883 __tmp.put_u8(self.target_component);
15884 __tmp.put_u8(self.len);
15885 for val in &self.data {
15886 __tmp.put_u8(*val);
15887 }
15888 if matches!(version, MavlinkVersion::V2) {
15889 let len = __tmp.len();
15890 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15891 } else {
15892 __tmp.len()
15893 }
15894 }
15895}
15896#[doc = "GPS sensor input message. This is a raw sensor value sent by the GPS. This is NOT the global position estimate of the system."]
15897#[doc = ""]
15898#[doc = "ID: 232"]
15899#[derive(Debug, Clone, PartialEq)]
15900#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15901#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15902#[cfg_attr(feature = "ts", derive(TS))]
15903#[cfg_attr(feature = "ts", ts(export))]
15904pub struct GPS_INPUT_DATA {
15905 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
15906 pub time_usec: u64,
15907 #[doc = "GPS time (from start of GPS week)"]
15908 pub time_week_ms: u32,
15909 #[doc = "Latitude (WGS84)"]
15910 pub lat: i32,
15911 #[doc = "Longitude (WGS84)"]
15912 pub lon: i32,
15913 #[doc = "Altitude (MSL). Positive for up."]
15914 pub alt: f32,
15915 #[doc = "GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX"]
15916 pub hdop: f32,
15917 #[doc = "GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX"]
15918 pub vdop: f32,
15919 #[doc = "GPS velocity in north direction in earth-fixed NED frame"]
15920 pub vn: f32,
15921 #[doc = "GPS velocity in east direction in earth-fixed NED frame"]
15922 pub ve: f32,
15923 #[doc = "GPS velocity in down direction in earth-fixed NED frame"]
15924 pub vd: f32,
15925 #[doc = "GPS speed accuracy"]
15926 pub speed_accuracy: f32,
15927 #[doc = "GPS horizontal accuracy"]
15928 pub horiz_accuracy: f32,
15929 #[doc = "GPS vertical accuracy"]
15930 pub vert_accuracy: f32,
15931 #[doc = "Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided."]
15932 pub ignore_flags: GpsInputIgnoreFlags,
15933 #[doc = "GPS week number"]
15934 pub time_week: u16,
15935 #[doc = "ID of the GPS for multiple GPS inputs"]
15936 pub gps_id: u8,
15937 #[doc = "0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK"]
15938 pub fix_type: u8,
15939 #[doc = "Number of satellites visible."]
15940 pub satellites_visible: u8,
15941 #[doc = "Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north"]
15942 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
15943 pub yaw: u16,
15944}
15945impl GPS_INPUT_DATA {
15946 pub const ENCODED_LEN: usize = 65usize;
15947 pub const DEFAULT: Self = Self {
15948 time_usec: 0_u64,
15949 time_week_ms: 0_u32,
15950 lat: 0_i32,
15951 lon: 0_i32,
15952 alt: 0.0_f32,
15953 hdop: 0.0_f32,
15954 vdop: 0.0_f32,
15955 vn: 0.0_f32,
15956 ve: 0.0_f32,
15957 vd: 0.0_f32,
15958 speed_accuracy: 0.0_f32,
15959 horiz_accuracy: 0.0_f32,
15960 vert_accuracy: 0.0_f32,
15961 ignore_flags: GpsInputIgnoreFlags::DEFAULT,
15962 time_week: 0_u16,
15963 gps_id: 0_u8,
15964 fix_type: 0_u8,
15965 satellites_visible: 0_u8,
15966 yaw: 0_u16,
15967 };
15968 #[cfg(feature = "arbitrary")]
15969 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15970 use arbitrary::{Arbitrary, Unstructured};
15971 let mut buf = [0u8; 1024];
15972 rng.fill_bytes(&mut buf);
15973 let mut unstructured = Unstructured::new(&buf);
15974 Self::arbitrary(&mut unstructured).unwrap_or_default()
15975 }
15976}
15977impl Default for GPS_INPUT_DATA {
15978 fn default() -> Self {
15979 Self::DEFAULT.clone()
15980 }
15981}
15982impl MessageData for GPS_INPUT_DATA {
15983 type Message = MavMessage;
15984 const ID: u32 = 232u32;
15985 const NAME: &'static str = "GPS_INPUT";
15986 const EXTRA_CRC: u8 = 151u8;
15987 const ENCODED_LEN: usize = 65usize;
15988 fn deser(
15989 _version: MavlinkVersion,
15990 __input: &[u8],
15991 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15992 let avail_len = __input.len();
15993 let mut payload_buf = [0; Self::ENCODED_LEN];
15994 let mut buf = if avail_len < Self::ENCODED_LEN {
15995 payload_buf[0..avail_len].copy_from_slice(__input);
15996 Bytes::new(&payload_buf)
15997 } else {
15998 Bytes::new(__input)
15999 };
16000 let mut __struct = Self::default();
16001 __struct.time_usec = buf.get_u64_le()?;
16002 __struct.time_week_ms = buf.get_u32_le()?;
16003 __struct.lat = buf.get_i32_le()?;
16004 __struct.lon = buf.get_i32_le()?;
16005 __struct.alt = buf.get_f32_le()?;
16006 __struct.hdop = buf.get_f32_le()?;
16007 __struct.vdop = buf.get_f32_le()?;
16008 __struct.vn = buf.get_f32_le()?;
16009 __struct.ve = buf.get_f32_le()?;
16010 __struct.vd = buf.get_f32_le()?;
16011 __struct.speed_accuracy = buf.get_f32_le()?;
16012 __struct.horiz_accuracy = buf.get_f32_le()?;
16013 __struct.vert_accuracy = buf.get_f32_le()?;
16014 let tmp = buf.get_u16_le()?;
16015 __struct.ignore_flags = GpsInputIgnoreFlags::from_bits(
16016 tmp as <GpsInputIgnoreFlags as Flags>::Bits,
16017 )
16018 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
16019 flag_type: "GpsInputIgnoreFlags",
16020 value: tmp as u64,
16021 })?;
16022 __struct.time_week = buf.get_u16_le()?;
16023 __struct.gps_id = buf.get_u8()?;
16024 __struct.fix_type = buf.get_u8()?;
16025 __struct.satellites_visible = buf.get_u8()?;
16026 __struct.yaw = buf.get_u16_le()?;
16027 Ok(__struct)
16028 }
16029 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16030 let mut __tmp = BytesMut::new(bytes);
16031 #[allow(clippy::absurd_extreme_comparisons)]
16032 #[allow(unused_comparisons)]
16033 if __tmp.remaining() < Self::ENCODED_LEN {
16034 panic!(
16035 "buffer is too small (need {} bytes, but got {})",
16036 Self::ENCODED_LEN,
16037 __tmp.remaining(),
16038 )
16039 }
16040 __tmp.put_u64_le(self.time_usec);
16041 __tmp.put_u32_le(self.time_week_ms);
16042 __tmp.put_i32_le(self.lat);
16043 __tmp.put_i32_le(self.lon);
16044 __tmp.put_f32_le(self.alt);
16045 __tmp.put_f32_le(self.hdop);
16046 __tmp.put_f32_le(self.vdop);
16047 __tmp.put_f32_le(self.vn);
16048 __tmp.put_f32_le(self.ve);
16049 __tmp.put_f32_le(self.vd);
16050 __tmp.put_f32_le(self.speed_accuracy);
16051 __tmp.put_f32_le(self.horiz_accuracy);
16052 __tmp.put_f32_le(self.vert_accuracy);
16053 __tmp.put_u16_le(self.ignore_flags.bits() as u16);
16054 __tmp.put_u16_le(self.time_week);
16055 __tmp.put_u8(self.gps_id);
16056 __tmp.put_u8(self.fix_type);
16057 __tmp.put_u8(self.satellites_visible);
16058 if matches!(version, MavlinkVersion::V2) {
16059 __tmp.put_u16_le(self.yaw);
16060 let len = __tmp.len();
16061 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16062 } else {
16063 __tmp.len()
16064 }
16065 }
16066}
16067#[doc = "The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION_INT for the global position estimate."]
16068#[doc = ""]
16069#[doc = "ID: 24"]
16070#[derive(Debug, Clone, PartialEq)]
16071#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16072#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16073#[cfg_attr(feature = "ts", derive(TS))]
16074#[cfg_attr(feature = "ts", ts(export))]
16075pub struct GPS_RAW_INT_DATA {
16076 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
16077 pub time_usec: u64,
16078 #[doc = "Latitude (WGS84, EGM96 ellipsoid)"]
16079 pub lat: i32,
16080 #[doc = "Longitude (WGS84, EGM96 ellipsoid)"]
16081 pub lon: i32,
16082 #[doc = "Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude."]
16083 pub alt: i32,
16084 #[doc = "GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
16085 pub eph: u16,
16086 #[doc = "GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
16087 pub epv: u16,
16088 #[doc = "GPS ground speed. If unknown, set to: UINT16_MAX"]
16089 pub vel: u16,
16090 #[doc = "Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX"]
16091 pub cog: u16,
16092 #[doc = "GPS fix type."]
16093 pub fix_type: GpsFixType,
16094 #[doc = "Number of satellites visible. If unknown, set to UINT8_MAX"]
16095 pub satellites_visible: u8,
16096 #[doc = "Altitude (above WGS84, EGM96 ellipsoid). Positive for up."]
16097 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16098 pub alt_ellipsoid: i32,
16099 #[doc = "Position uncertainty."]
16100 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16101 pub h_acc: u32,
16102 #[doc = "Altitude uncertainty."]
16103 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16104 pub v_acc: u32,
16105 #[doc = "Speed uncertainty."]
16106 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16107 pub vel_acc: u32,
16108 #[doc = "Heading / track uncertainty"]
16109 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16110 pub hdg_acc: u32,
16111 #[doc = "Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north."]
16112 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16113 pub yaw: u16,
16114}
16115impl GPS_RAW_INT_DATA {
16116 pub const ENCODED_LEN: usize = 52usize;
16117 pub const DEFAULT: Self = Self {
16118 time_usec: 0_u64,
16119 lat: 0_i32,
16120 lon: 0_i32,
16121 alt: 0_i32,
16122 eph: 0_u16,
16123 epv: 0_u16,
16124 vel: 0_u16,
16125 cog: 0_u16,
16126 fix_type: GpsFixType::DEFAULT,
16127 satellites_visible: 0_u8,
16128 alt_ellipsoid: 0_i32,
16129 h_acc: 0_u32,
16130 v_acc: 0_u32,
16131 vel_acc: 0_u32,
16132 hdg_acc: 0_u32,
16133 yaw: 0_u16,
16134 };
16135 #[cfg(feature = "arbitrary")]
16136 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16137 use arbitrary::{Arbitrary, Unstructured};
16138 let mut buf = [0u8; 1024];
16139 rng.fill_bytes(&mut buf);
16140 let mut unstructured = Unstructured::new(&buf);
16141 Self::arbitrary(&mut unstructured).unwrap_or_default()
16142 }
16143}
16144impl Default for GPS_RAW_INT_DATA {
16145 fn default() -> Self {
16146 Self::DEFAULT.clone()
16147 }
16148}
16149impl MessageData for GPS_RAW_INT_DATA {
16150 type Message = MavMessage;
16151 const ID: u32 = 24u32;
16152 const NAME: &'static str = "GPS_RAW_INT";
16153 const EXTRA_CRC: u8 = 24u8;
16154 const ENCODED_LEN: usize = 52usize;
16155 fn deser(
16156 _version: MavlinkVersion,
16157 __input: &[u8],
16158 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16159 let avail_len = __input.len();
16160 let mut payload_buf = [0; Self::ENCODED_LEN];
16161 let mut buf = if avail_len < Self::ENCODED_LEN {
16162 payload_buf[0..avail_len].copy_from_slice(__input);
16163 Bytes::new(&payload_buf)
16164 } else {
16165 Bytes::new(__input)
16166 };
16167 let mut __struct = Self::default();
16168 __struct.time_usec = buf.get_u64_le()?;
16169 __struct.lat = buf.get_i32_le()?;
16170 __struct.lon = buf.get_i32_le()?;
16171 __struct.alt = buf.get_i32_le()?;
16172 __struct.eph = buf.get_u16_le()?;
16173 __struct.epv = buf.get_u16_le()?;
16174 __struct.vel = buf.get_u16_le()?;
16175 __struct.cog = buf.get_u16_le()?;
16176 let tmp = buf.get_u8()?;
16177 __struct.fix_type =
16178 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
16179 enum_type: "GpsFixType",
16180 value: tmp as u64,
16181 })?;
16182 __struct.satellites_visible = buf.get_u8()?;
16183 __struct.alt_ellipsoid = buf.get_i32_le()?;
16184 __struct.h_acc = buf.get_u32_le()?;
16185 __struct.v_acc = buf.get_u32_le()?;
16186 __struct.vel_acc = buf.get_u32_le()?;
16187 __struct.hdg_acc = buf.get_u32_le()?;
16188 __struct.yaw = buf.get_u16_le()?;
16189 Ok(__struct)
16190 }
16191 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16192 let mut __tmp = BytesMut::new(bytes);
16193 #[allow(clippy::absurd_extreme_comparisons)]
16194 #[allow(unused_comparisons)]
16195 if __tmp.remaining() < Self::ENCODED_LEN {
16196 panic!(
16197 "buffer is too small (need {} bytes, but got {})",
16198 Self::ENCODED_LEN,
16199 __tmp.remaining(),
16200 )
16201 }
16202 __tmp.put_u64_le(self.time_usec);
16203 __tmp.put_i32_le(self.lat);
16204 __tmp.put_i32_le(self.lon);
16205 __tmp.put_i32_le(self.alt);
16206 __tmp.put_u16_le(self.eph);
16207 __tmp.put_u16_le(self.epv);
16208 __tmp.put_u16_le(self.vel);
16209 __tmp.put_u16_le(self.cog);
16210 __tmp.put_u8(self.fix_type as u8);
16211 __tmp.put_u8(self.satellites_visible);
16212 if matches!(version, MavlinkVersion::V2) {
16213 __tmp.put_i32_le(self.alt_ellipsoid);
16214 __tmp.put_u32_le(self.h_acc);
16215 __tmp.put_u32_le(self.v_acc);
16216 __tmp.put_u32_le(self.vel_acc);
16217 __tmp.put_u32_le(self.hdg_acc);
16218 __tmp.put_u16_le(self.yaw);
16219 let len = __tmp.len();
16220 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16221 } else {
16222 __tmp.len()
16223 }
16224 }
16225}
16226#[doc = "RTCM message for injecting into the onboard GPS (used for DGPS)."]
16227#[doc = ""]
16228#[doc = "ID: 233"]
16229#[derive(Debug, Clone, PartialEq)]
16230#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16231#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16232#[cfg_attr(feature = "ts", derive(TS))]
16233#[cfg_attr(feature = "ts", ts(export))]
16234pub struct GPS_RTCM_DATA_DATA {
16235 #[doc = "LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order."]
16236 pub flags: u8,
16237 #[doc = "data length"]
16238 pub len: u8,
16239 #[doc = "RTCM message (may be fragmented)"]
16240 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16241 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
16242 pub data: [u8; 180],
16243}
16244impl GPS_RTCM_DATA_DATA {
16245 pub const ENCODED_LEN: usize = 182usize;
16246 pub const DEFAULT: Self = Self {
16247 flags: 0_u8,
16248 len: 0_u8,
16249 data: [0_u8; 180usize],
16250 };
16251 #[cfg(feature = "arbitrary")]
16252 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16253 use arbitrary::{Arbitrary, Unstructured};
16254 let mut buf = [0u8; 1024];
16255 rng.fill_bytes(&mut buf);
16256 let mut unstructured = Unstructured::new(&buf);
16257 Self::arbitrary(&mut unstructured).unwrap_or_default()
16258 }
16259}
16260impl Default for GPS_RTCM_DATA_DATA {
16261 fn default() -> Self {
16262 Self::DEFAULT.clone()
16263 }
16264}
16265impl MessageData for GPS_RTCM_DATA_DATA {
16266 type Message = MavMessage;
16267 const ID: u32 = 233u32;
16268 const NAME: &'static str = "GPS_RTCM_DATA";
16269 const EXTRA_CRC: u8 = 35u8;
16270 const ENCODED_LEN: usize = 182usize;
16271 fn deser(
16272 _version: MavlinkVersion,
16273 __input: &[u8],
16274 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16275 let avail_len = __input.len();
16276 let mut payload_buf = [0; Self::ENCODED_LEN];
16277 let mut buf = if avail_len < Self::ENCODED_LEN {
16278 payload_buf[0..avail_len].copy_from_slice(__input);
16279 Bytes::new(&payload_buf)
16280 } else {
16281 Bytes::new(__input)
16282 };
16283 let mut __struct = Self::default();
16284 __struct.flags = buf.get_u8()?;
16285 __struct.len = buf.get_u8()?;
16286 for v in &mut __struct.data {
16287 let val = buf.get_u8()?;
16288 *v = val;
16289 }
16290 Ok(__struct)
16291 }
16292 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16293 let mut __tmp = BytesMut::new(bytes);
16294 #[allow(clippy::absurd_extreme_comparisons)]
16295 #[allow(unused_comparisons)]
16296 if __tmp.remaining() < Self::ENCODED_LEN {
16297 panic!(
16298 "buffer is too small (need {} bytes, but got {})",
16299 Self::ENCODED_LEN,
16300 __tmp.remaining(),
16301 )
16302 }
16303 __tmp.put_u8(self.flags);
16304 __tmp.put_u8(self.len);
16305 for val in &self.data {
16306 __tmp.put_u8(*val);
16307 }
16308 if matches!(version, MavlinkVersion::V2) {
16309 let len = __tmp.len();
16310 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16311 } else {
16312 __tmp.len()
16313 }
16314 }
16315}
16316#[doc = "RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting."]
16317#[doc = ""]
16318#[doc = "ID: 127"]
16319#[derive(Debug, Clone, PartialEq)]
16320#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16321#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16322#[cfg_attr(feature = "ts", derive(TS))]
16323#[cfg_attr(feature = "ts", ts(export))]
16324pub struct GPS_RTK_DATA {
16325 #[doc = "Time since boot of last baseline message received."]
16326 pub time_last_baseline_ms: u32,
16327 #[doc = "GPS Time of Week of last baseline"]
16328 pub tow: u32,
16329 #[doc = "Current baseline in ECEF x or NED north component."]
16330 pub baseline_a_mm: i32,
16331 #[doc = "Current baseline in ECEF y or NED east component."]
16332 pub baseline_b_mm: i32,
16333 #[doc = "Current baseline in ECEF z or NED down component."]
16334 pub baseline_c_mm: i32,
16335 #[doc = "Current estimate of baseline accuracy."]
16336 pub accuracy: u32,
16337 #[doc = "Current number of integer ambiguity hypotheses."]
16338 pub iar_num_hypotheses: i32,
16339 #[doc = "GPS Week Number of last baseline"]
16340 pub wn: u16,
16341 #[doc = "Identification of connected RTK receiver."]
16342 pub rtk_receiver_id: u8,
16343 #[doc = "GPS-specific health report for RTK data."]
16344 pub rtk_health: u8,
16345 #[doc = "Rate of baseline messages being received by GPS"]
16346 pub rtk_rate: u8,
16347 #[doc = "Current number of sats used for RTK calculation."]
16348 pub nsats: u8,
16349 #[doc = "Coordinate system of baseline"]
16350 pub baseline_coords_type: RtkBaselineCoordinateSystem,
16351}
16352impl GPS_RTK_DATA {
16353 pub const ENCODED_LEN: usize = 35usize;
16354 pub const DEFAULT: Self = Self {
16355 time_last_baseline_ms: 0_u32,
16356 tow: 0_u32,
16357 baseline_a_mm: 0_i32,
16358 baseline_b_mm: 0_i32,
16359 baseline_c_mm: 0_i32,
16360 accuracy: 0_u32,
16361 iar_num_hypotheses: 0_i32,
16362 wn: 0_u16,
16363 rtk_receiver_id: 0_u8,
16364 rtk_health: 0_u8,
16365 rtk_rate: 0_u8,
16366 nsats: 0_u8,
16367 baseline_coords_type: RtkBaselineCoordinateSystem::DEFAULT,
16368 };
16369 #[cfg(feature = "arbitrary")]
16370 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16371 use arbitrary::{Arbitrary, Unstructured};
16372 let mut buf = [0u8; 1024];
16373 rng.fill_bytes(&mut buf);
16374 let mut unstructured = Unstructured::new(&buf);
16375 Self::arbitrary(&mut unstructured).unwrap_or_default()
16376 }
16377}
16378impl Default for GPS_RTK_DATA {
16379 fn default() -> Self {
16380 Self::DEFAULT.clone()
16381 }
16382}
16383impl MessageData for GPS_RTK_DATA {
16384 type Message = MavMessage;
16385 const ID: u32 = 127u32;
16386 const NAME: &'static str = "GPS_RTK";
16387 const EXTRA_CRC: u8 = 25u8;
16388 const ENCODED_LEN: usize = 35usize;
16389 fn deser(
16390 _version: MavlinkVersion,
16391 __input: &[u8],
16392 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16393 let avail_len = __input.len();
16394 let mut payload_buf = [0; Self::ENCODED_LEN];
16395 let mut buf = if avail_len < Self::ENCODED_LEN {
16396 payload_buf[0..avail_len].copy_from_slice(__input);
16397 Bytes::new(&payload_buf)
16398 } else {
16399 Bytes::new(__input)
16400 };
16401 let mut __struct = Self::default();
16402 __struct.time_last_baseline_ms = buf.get_u32_le()?;
16403 __struct.tow = buf.get_u32_le()?;
16404 __struct.baseline_a_mm = buf.get_i32_le()?;
16405 __struct.baseline_b_mm = buf.get_i32_le()?;
16406 __struct.baseline_c_mm = buf.get_i32_le()?;
16407 __struct.accuracy = buf.get_u32_le()?;
16408 __struct.iar_num_hypotheses = buf.get_i32_le()?;
16409 __struct.wn = buf.get_u16_le()?;
16410 __struct.rtk_receiver_id = buf.get_u8()?;
16411 __struct.rtk_health = buf.get_u8()?;
16412 __struct.rtk_rate = buf.get_u8()?;
16413 __struct.nsats = buf.get_u8()?;
16414 let tmp = buf.get_u8()?;
16415 __struct.baseline_coords_type =
16416 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
16417 enum_type: "RtkBaselineCoordinateSystem",
16418 value: tmp as u64,
16419 })?;
16420 Ok(__struct)
16421 }
16422 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16423 let mut __tmp = BytesMut::new(bytes);
16424 #[allow(clippy::absurd_extreme_comparisons)]
16425 #[allow(unused_comparisons)]
16426 if __tmp.remaining() < Self::ENCODED_LEN {
16427 panic!(
16428 "buffer is too small (need {} bytes, but got {})",
16429 Self::ENCODED_LEN,
16430 __tmp.remaining(),
16431 )
16432 }
16433 __tmp.put_u32_le(self.time_last_baseline_ms);
16434 __tmp.put_u32_le(self.tow);
16435 __tmp.put_i32_le(self.baseline_a_mm);
16436 __tmp.put_i32_le(self.baseline_b_mm);
16437 __tmp.put_i32_le(self.baseline_c_mm);
16438 __tmp.put_u32_le(self.accuracy);
16439 __tmp.put_i32_le(self.iar_num_hypotheses);
16440 __tmp.put_u16_le(self.wn);
16441 __tmp.put_u8(self.rtk_receiver_id);
16442 __tmp.put_u8(self.rtk_health);
16443 __tmp.put_u8(self.rtk_rate);
16444 __tmp.put_u8(self.nsats);
16445 __tmp.put_u8(self.baseline_coords_type as u8);
16446 if matches!(version, MavlinkVersion::V2) {
16447 let len = __tmp.len();
16448 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16449 } else {
16450 __tmp.len()
16451 }
16452 }
16453}
16454#[doc = "The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION_INT for the global position estimate. This message can contain information for up to 20 satellites."]
16455#[doc = ""]
16456#[doc = "ID: 25"]
16457#[derive(Debug, Clone, PartialEq)]
16458#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16459#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16460#[cfg_attr(feature = "ts", derive(TS))]
16461#[cfg_attr(feature = "ts", ts(export))]
16462pub struct GPS_STATUS_DATA {
16463 #[doc = "Number of satellites visible"]
16464 pub satellites_visible: u8,
16465 #[doc = "Global satellite ID"]
16466 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16467 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
16468 pub satellite_prn: [u8; 20],
16469 #[doc = "0: Satellite not used, 1: used for localization"]
16470 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16471 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
16472 pub satellite_used: [u8; 20],
16473 #[doc = "Elevation (0: right on top of receiver, 90: on the horizon) of satellite"]
16474 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16475 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
16476 pub satellite_elevation: [u8; 20],
16477 #[doc = "Direction of satellite, 0: 0 deg, 255: 360 deg."]
16478 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16479 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
16480 pub satellite_azimuth: [u8; 20],
16481 #[doc = "Signal to noise ratio of satellite"]
16482 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16483 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
16484 pub satellite_snr: [u8; 20],
16485}
16486impl GPS_STATUS_DATA {
16487 pub const ENCODED_LEN: usize = 101usize;
16488 pub const DEFAULT: Self = Self {
16489 satellites_visible: 0_u8,
16490 satellite_prn: [0_u8; 20usize],
16491 satellite_used: [0_u8; 20usize],
16492 satellite_elevation: [0_u8; 20usize],
16493 satellite_azimuth: [0_u8; 20usize],
16494 satellite_snr: [0_u8; 20usize],
16495 };
16496 #[cfg(feature = "arbitrary")]
16497 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16498 use arbitrary::{Arbitrary, Unstructured};
16499 let mut buf = [0u8; 1024];
16500 rng.fill_bytes(&mut buf);
16501 let mut unstructured = Unstructured::new(&buf);
16502 Self::arbitrary(&mut unstructured).unwrap_or_default()
16503 }
16504}
16505impl Default for GPS_STATUS_DATA {
16506 fn default() -> Self {
16507 Self::DEFAULT.clone()
16508 }
16509}
16510impl MessageData for GPS_STATUS_DATA {
16511 type Message = MavMessage;
16512 const ID: u32 = 25u32;
16513 const NAME: &'static str = "GPS_STATUS";
16514 const EXTRA_CRC: u8 = 23u8;
16515 const ENCODED_LEN: usize = 101usize;
16516 fn deser(
16517 _version: MavlinkVersion,
16518 __input: &[u8],
16519 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16520 let avail_len = __input.len();
16521 let mut payload_buf = [0; Self::ENCODED_LEN];
16522 let mut buf = if avail_len < Self::ENCODED_LEN {
16523 payload_buf[0..avail_len].copy_from_slice(__input);
16524 Bytes::new(&payload_buf)
16525 } else {
16526 Bytes::new(__input)
16527 };
16528 let mut __struct = Self::default();
16529 __struct.satellites_visible = buf.get_u8()?;
16530 for v in &mut __struct.satellite_prn {
16531 let val = buf.get_u8()?;
16532 *v = val;
16533 }
16534 for v in &mut __struct.satellite_used {
16535 let val = buf.get_u8()?;
16536 *v = val;
16537 }
16538 for v in &mut __struct.satellite_elevation {
16539 let val = buf.get_u8()?;
16540 *v = val;
16541 }
16542 for v in &mut __struct.satellite_azimuth {
16543 let val = buf.get_u8()?;
16544 *v = val;
16545 }
16546 for v in &mut __struct.satellite_snr {
16547 let val = buf.get_u8()?;
16548 *v = val;
16549 }
16550 Ok(__struct)
16551 }
16552 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16553 let mut __tmp = BytesMut::new(bytes);
16554 #[allow(clippy::absurd_extreme_comparisons)]
16555 #[allow(unused_comparisons)]
16556 if __tmp.remaining() < Self::ENCODED_LEN {
16557 panic!(
16558 "buffer is too small (need {} bytes, but got {})",
16559 Self::ENCODED_LEN,
16560 __tmp.remaining(),
16561 )
16562 }
16563 __tmp.put_u8(self.satellites_visible);
16564 for val in &self.satellite_prn {
16565 __tmp.put_u8(*val);
16566 }
16567 for val in &self.satellite_used {
16568 __tmp.put_u8(*val);
16569 }
16570 for val in &self.satellite_elevation {
16571 __tmp.put_u8(*val);
16572 }
16573 for val in &self.satellite_azimuth {
16574 __tmp.put_u8(*val);
16575 }
16576 for val in &self.satellite_snr {
16577 __tmp.put_u8(*val);
16578 }
16579 if matches!(version, MavlinkVersion::V2) {
16580 let len = __tmp.len();
16581 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16582 } else {
16583 __tmp.len()
16584 }
16585 }
16586}
16587#[doc = "The heartbeat message shows that a system or component is present and responding. The type and autopilot fields (along with the message component id), allow the receiving system to treat further messages from this system appropriately (e.g. by laying out the user interface based on the autopilot). This microservice is documented at <https://mavlink.io/en/services/heartbeat.html>."]
16588#[doc = ""]
16589#[doc = "ID: 0"]
16590#[derive(Debug, Clone, PartialEq)]
16591#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16592#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16593#[cfg_attr(feature = "ts", derive(TS))]
16594#[cfg_attr(feature = "ts", ts(export))]
16595pub struct HEARTBEAT_DATA {
16596 #[doc = "A bitfield for use for autopilot-specific flags"]
16597 pub custom_mode: u32,
16598 #[doc = "Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type."]
16599 pub mavtype: MavType,
16600 #[doc = "Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers."]
16601 pub autopilot: MavAutopilot,
16602 #[doc = "System mode bitmap."]
16603 pub base_mode: MavModeFlag,
16604 #[doc = "System status flag."]
16605 pub system_status: MavState,
16606 #[doc = "MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version"]
16607 pub mavlink_version: u8,
16608}
16609impl HEARTBEAT_DATA {
16610 pub const ENCODED_LEN: usize = 9usize;
16611 pub const DEFAULT: Self = Self {
16612 custom_mode: 0_u32,
16613 mavtype: MavType::DEFAULT,
16614 autopilot: MavAutopilot::DEFAULT,
16615 base_mode: MavModeFlag::DEFAULT,
16616 system_status: MavState::DEFAULT,
16617 mavlink_version: MINOR_MAVLINK_VERSION,
16618 };
16619 #[cfg(feature = "arbitrary")]
16620 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16621 use arbitrary::{Arbitrary, Unstructured};
16622 let mut buf = [0u8; 1024];
16623 rng.fill_bytes(&mut buf);
16624 let mut unstructured = Unstructured::new(&buf);
16625 Self::arbitrary(&mut unstructured).unwrap_or_default()
16626 }
16627}
16628impl Default for HEARTBEAT_DATA {
16629 fn default() -> Self {
16630 Self::DEFAULT.clone()
16631 }
16632}
16633impl MessageData for HEARTBEAT_DATA {
16634 type Message = MavMessage;
16635 const ID: u32 = 0u32;
16636 const NAME: &'static str = "HEARTBEAT";
16637 const EXTRA_CRC: u8 = 50u8;
16638 const ENCODED_LEN: usize = 9usize;
16639 fn deser(
16640 _version: MavlinkVersion,
16641 __input: &[u8],
16642 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16643 let avail_len = __input.len();
16644 let mut payload_buf = [0; Self::ENCODED_LEN];
16645 let mut buf = if avail_len < Self::ENCODED_LEN {
16646 payload_buf[0..avail_len].copy_from_slice(__input);
16647 Bytes::new(&payload_buf)
16648 } else {
16649 Bytes::new(__input)
16650 };
16651 let mut __struct = Self::default();
16652 __struct.custom_mode = buf.get_u32_le()?;
16653 let tmp = buf.get_u8()?;
16654 __struct.mavtype =
16655 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
16656 enum_type: "MavType",
16657 value: tmp as u64,
16658 })?;
16659 let tmp = buf.get_u8()?;
16660 __struct.autopilot =
16661 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
16662 enum_type: "MavAutopilot",
16663 value: tmp as u64,
16664 })?;
16665 let tmp = buf.get_u8()?;
16666 __struct.base_mode = MavModeFlag::from_bits(tmp as <MavModeFlag as Flags>::Bits).ok_or(
16667 ::mavlink_core::error::ParserError::InvalidFlag {
16668 flag_type: "MavModeFlag",
16669 value: tmp as u64,
16670 },
16671 )?;
16672 let tmp = buf.get_u8()?;
16673 __struct.system_status =
16674 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
16675 enum_type: "MavState",
16676 value: tmp as u64,
16677 })?;
16678 __struct.mavlink_version = buf.get_u8()?;
16679 Ok(__struct)
16680 }
16681 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16682 let mut __tmp = BytesMut::new(bytes);
16683 #[allow(clippy::absurd_extreme_comparisons)]
16684 #[allow(unused_comparisons)]
16685 if __tmp.remaining() < Self::ENCODED_LEN {
16686 panic!(
16687 "buffer is too small (need {} bytes, but got {})",
16688 Self::ENCODED_LEN,
16689 __tmp.remaining(),
16690 )
16691 }
16692 __tmp.put_u32_le(self.custom_mode);
16693 __tmp.put_u8(self.mavtype as u8);
16694 __tmp.put_u8(self.autopilot as u8);
16695 __tmp.put_u8(self.base_mode.bits() as u8);
16696 __tmp.put_u8(self.system_status as u8);
16697 __tmp.put_u8(self.mavlink_version);
16698 if matches!(version, MavlinkVersion::V2) {
16699 let len = __tmp.len();
16700 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16701 } else {
16702 __tmp.len()
16703 }
16704 }
16705}
16706#[doc = "The IMU readings in SI units in NED body frame."]
16707#[doc = ""]
16708#[doc = "ID: 105"]
16709#[derive(Debug, Clone, PartialEq)]
16710#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16711#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16712#[cfg_attr(feature = "ts", derive(TS))]
16713#[cfg_attr(feature = "ts", ts(export))]
16714pub struct HIGHRES_IMU_DATA {
16715 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
16716 pub time_usec: u64,
16717 #[doc = "X acceleration"]
16718 pub xacc: f32,
16719 #[doc = "Y acceleration"]
16720 pub yacc: f32,
16721 #[doc = "Z acceleration"]
16722 pub zacc: f32,
16723 #[doc = "Angular speed around X axis"]
16724 pub xgyro: f32,
16725 #[doc = "Angular speed around Y axis"]
16726 pub ygyro: f32,
16727 #[doc = "Angular speed around Z axis"]
16728 pub zgyro: f32,
16729 #[doc = "X Magnetic field"]
16730 pub xmag: f32,
16731 #[doc = "Y Magnetic field"]
16732 pub ymag: f32,
16733 #[doc = "Z Magnetic field"]
16734 pub zmag: f32,
16735 #[doc = "Absolute pressure"]
16736 pub abs_pressure: f32,
16737 #[doc = "Differential pressure"]
16738 pub diff_pressure: f32,
16739 #[doc = "Altitude calculated from pressure"]
16740 pub pressure_alt: f32,
16741 #[doc = "Temperature"]
16742 pub temperature: f32,
16743 #[doc = "Bitmap for fields that have updated since last message"]
16744 pub fields_updated: HighresImuUpdatedFlags,
16745 #[doc = "Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)"]
16746 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16747 pub id: u8,
16748}
16749impl HIGHRES_IMU_DATA {
16750 pub const ENCODED_LEN: usize = 63usize;
16751 pub const DEFAULT: Self = Self {
16752 time_usec: 0_u64,
16753 xacc: 0.0_f32,
16754 yacc: 0.0_f32,
16755 zacc: 0.0_f32,
16756 xgyro: 0.0_f32,
16757 ygyro: 0.0_f32,
16758 zgyro: 0.0_f32,
16759 xmag: 0.0_f32,
16760 ymag: 0.0_f32,
16761 zmag: 0.0_f32,
16762 abs_pressure: 0.0_f32,
16763 diff_pressure: 0.0_f32,
16764 pressure_alt: 0.0_f32,
16765 temperature: 0.0_f32,
16766 fields_updated: HighresImuUpdatedFlags::DEFAULT,
16767 id: 0_u8,
16768 };
16769 #[cfg(feature = "arbitrary")]
16770 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16771 use arbitrary::{Arbitrary, Unstructured};
16772 let mut buf = [0u8; 1024];
16773 rng.fill_bytes(&mut buf);
16774 let mut unstructured = Unstructured::new(&buf);
16775 Self::arbitrary(&mut unstructured).unwrap_or_default()
16776 }
16777}
16778impl Default for HIGHRES_IMU_DATA {
16779 fn default() -> Self {
16780 Self::DEFAULT.clone()
16781 }
16782}
16783impl MessageData for HIGHRES_IMU_DATA {
16784 type Message = MavMessage;
16785 const ID: u32 = 105u32;
16786 const NAME: &'static str = "HIGHRES_IMU";
16787 const EXTRA_CRC: u8 = 93u8;
16788 const ENCODED_LEN: usize = 63usize;
16789 fn deser(
16790 _version: MavlinkVersion,
16791 __input: &[u8],
16792 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16793 let avail_len = __input.len();
16794 let mut payload_buf = [0; Self::ENCODED_LEN];
16795 let mut buf = if avail_len < Self::ENCODED_LEN {
16796 payload_buf[0..avail_len].copy_from_slice(__input);
16797 Bytes::new(&payload_buf)
16798 } else {
16799 Bytes::new(__input)
16800 };
16801 let mut __struct = Self::default();
16802 __struct.time_usec = buf.get_u64_le()?;
16803 __struct.xacc = buf.get_f32_le()?;
16804 __struct.yacc = buf.get_f32_le()?;
16805 __struct.zacc = buf.get_f32_le()?;
16806 __struct.xgyro = buf.get_f32_le()?;
16807 __struct.ygyro = buf.get_f32_le()?;
16808 __struct.zgyro = buf.get_f32_le()?;
16809 __struct.xmag = buf.get_f32_le()?;
16810 __struct.ymag = buf.get_f32_le()?;
16811 __struct.zmag = buf.get_f32_le()?;
16812 __struct.abs_pressure = buf.get_f32_le()?;
16813 __struct.diff_pressure = buf.get_f32_le()?;
16814 __struct.pressure_alt = buf.get_f32_le()?;
16815 __struct.temperature = buf.get_f32_le()?;
16816 let tmp = buf.get_u16_le()?;
16817 __struct.fields_updated =
16818 HighresImuUpdatedFlags::from_bits(tmp as <HighresImuUpdatedFlags as Flags>::Bits)
16819 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
16820 flag_type: "HighresImuUpdatedFlags",
16821 value: tmp as u64,
16822 })?;
16823 __struct.id = buf.get_u8()?;
16824 Ok(__struct)
16825 }
16826 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16827 let mut __tmp = BytesMut::new(bytes);
16828 #[allow(clippy::absurd_extreme_comparisons)]
16829 #[allow(unused_comparisons)]
16830 if __tmp.remaining() < Self::ENCODED_LEN {
16831 panic!(
16832 "buffer is too small (need {} bytes, but got {})",
16833 Self::ENCODED_LEN,
16834 __tmp.remaining(),
16835 )
16836 }
16837 __tmp.put_u64_le(self.time_usec);
16838 __tmp.put_f32_le(self.xacc);
16839 __tmp.put_f32_le(self.yacc);
16840 __tmp.put_f32_le(self.zacc);
16841 __tmp.put_f32_le(self.xgyro);
16842 __tmp.put_f32_le(self.ygyro);
16843 __tmp.put_f32_le(self.zgyro);
16844 __tmp.put_f32_le(self.xmag);
16845 __tmp.put_f32_le(self.ymag);
16846 __tmp.put_f32_le(self.zmag);
16847 __tmp.put_f32_le(self.abs_pressure);
16848 __tmp.put_f32_le(self.diff_pressure);
16849 __tmp.put_f32_le(self.pressure_alt);
16850 __tmp.put_f32_le(self.temperature);
16851 __tmp.put_u16_le(self.fields_updated.bits() as u16);
16852 if matches!(version, MavlinkVersion::V2) {
16853 __tmp.put_u8(self.id);
16854 let len = __tmp.len();
16855 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16856 } else {
16857 __tmp.len()
16858 }
16859 }
16860}
16861#[deprecated = " See `HIGH_LATENCY2` (Deprecated since 2020-10)"]
16862#[doc = "Message appropriate for high latency connections like Iridium."]
16863#[doc = ""]
16864#[doc = "ID: 234"]
16865#[derive(Debug, Clone, PartialEq)]
16866#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16867#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16868#[cfg_attr(feature = "ts", derive(TS))]
16869#[cfg_attr(feature = "ts", ts(export))]
16870pub struct HIGH_LATENCY_DATA {
16871 #[doc = "A bitfield for use for autopilot-specific flags."]
16872 pub custom_mode: u32,
16873 #[doc = "Latitude"]
16874 pub latitude: i32,
16875 #[doc = "Longitude"]
16876 pub longitude: i32,
16877 #[doc = "roll"]
16878 pub roll: i16,
16879 #[doc = "pitch"]
16880 pub pitch: i16,
16881 #[doc = "heading"]
16882 pub heading: u16,
16883 #[doc = "heading setpoint"]
16884 pub heading_sp: i16,
16885 #[doc = "Altitude above mean sea level"]
16886 pub altitude_amsl: i16,
16887 #[doc = "Altitude setpoint relative to the home position"]
16888 pub altitude_sp: i16,
16889 #[doc = "distance to target"]
16890 pub wp_distance: u16,
16891 #[doc = "Bitmap of enabled system modes."]
16892 pub base_mode: MavModeFlag,
16893 #[doc = "The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown."]
16894 pub landed_state: MavLandedState,
16895 #[doc = "throttle (percentage)"]
16896 pub throttle: i8,
16897 #[doc = "airspeed"]
16898 pub airspeed: u8,
16899 #[doc = "airspeed setpoint"]
16900 pub airspeed_sp: u8,
16901 #[doc = "groundspeed"]
16902 pub groundspeed: u8,
16903 #[doc = "climb rate"]
16904 pub climb_rate: i8,
16905 #[doc = "Number of satellites visible. If unknown, set to UINT8_MAX"]
16906 pub gps_nsat: u8,
16907 #[doc = "GPS Fix type."]
16908 pub gps_fix_type: GpsFixType,
16909 #[doc = "Remaining battery (percentage)"]
16910 pub battery_remaining: u8,
16911 #[doc = "Autopilot temperature (degrees C)"]
16912 pub temperature: i8,
16913 #[doc = "Air temperature (degrees C) from airspeed sensor"]
16914 pub temperature_air: i8,
16915 #[doc = "failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)"]
16916 pub failsafe: u8,
16917 #[doc = "current waypoint number"]
16918 pub wp_num: u8,
16919}
16920impl HIGH_LATENCY_DATA {
16921 pub const ENCODED_LEN: usize = 40usize;
16922 pub const DEFAULT: Self = Self {
16923 custom_mode: 0_u32,
16924 latitude: 0_i32,
16925 longitude: 0_i32,
16926 roll: 0_i16,
16927 pitch: 0_i16,
16928 heading: 0_u16,
16929 heading_sp: 0_i16,
16930 altitude_amsl: 0_i16,
16931 altitude_sp: 0_i16,
16932 wp_distance: 0_u16,
16933 base_mode: MavModeFlag::DEFAULT,
16934 landed_state: MavLandedState::DEFAULT,
16935 throttle: 0_i8,
16936 airspeed: 0_u8,
16937 airspeed_sp: 0_u8,
16938 groundspeed: 0_u8,
16939 climb_rate: 0_i8,
16940 gps_nsat: 0_u8,
16941 gps_fix_type: GpsFixType::DEFAULT,
16942 battery_remaining: 0_u8,
16943 temperature: 0_i8,
16944 temperature_air: 0_i8,
16945 failsafe: 0_u8,
16946 wp_num: 0_u8,
16947 };
16948 #[cfg(feature = "arbitrary")]
16949 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16950 use arbitrary::{Arbitrary, Unstructured};
16951 let mut buf = [0u8; 1024];
16952 rng.fill_bytes(&mut buf);
16953 let mut unstructured = Unstructured::new(&buf);
16954 Self::arbitrary(&mut unstructured).unwrap_or_default()
16955 }
16956}
16957impl Default for HIGH_LATENCY_DATA {
16958 fn default() -> Self {
16959 Self::DEFAULT.clone()
16960 }
16961}
16962impl MessageData for HIGH_LATENCY_DATA {
16963 type Message = MavMessage;
16964 const ID: u32 = 234u32;
16965 const NAME: &'static str = "HIGH_LATENCY";
16966 const EXTRA_CRC: u8 = 150u8;
16967 const ENCODED_LEN: usize = 40usize;
16968 fn deser(
16969 _version: MavlinkVersion,
16970 __input: &[u8],
16971 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16972 let avail_len = __input.len();
16973 let mut payload_buf = [0; Self::ENCODED_LEN];
16974 let mut buf = if avail_len < Self::ENCODED_LEN {
16975 payload_buf[0..avail_len].copy_from_slice(__input);
16976 Bytes::new(&payload_buf)
16977 } else {
16978 Bytes::new(__input)
16979 };
16980 let mut __struct = Self::default();
16981 __struct.custom_mode = buf.get_u32_le()?;
16982 __struct.latitude = buf.get_i32_le()?;
16983 __struct.longitude = buf.get_i32_le()?;
16984 __struct.roll = buf.get_i16_le()?;
16985 __struct.pitch = buf.get_i16_le()?;
16986 __struct.heading = buf.get_u16_le()?;
16987 __struct.heading_sp = buf.get_i16_le()?;
16988 __struct.altitude_amsl = buf.get_i16_le()?;
16989 __struct.altitude_sp = buf.get_i16_le()?;
16990 __struct.wp_distance = buf.get_u16_le()?;
16991 let tmp = buf.get_u8()?;
16992 __struct.base_mode = MavModeFlag::from_bits(tmp as <MavModeFlag as Flags>::Bits).ok_or(
16993 ::mavlink_core::error::ParserError::InvalidFlag {
16994 flag_type: "MavModeFlag",
16995 value: tmp as u64,
16996 },
16997 )?;
16998 let tmp = buf.get_u8()?;
16999 __struct.landed_state =
17000 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
17001 enum_type: "MavLandedState",
17002 value: tmp as u64,
17003 })?;
17004 __struct.throttle = buf.get_i8()?;
17005 __struct.airspeed = buf.get_u8()?;
17006 __struct.airspeed_sp = buf.get_u8()?;
17007 __struct.groundspeed = buf.get_u8()?;
17008 __struct.climb_rate = buf.get_i8()?;
17009 __struct.gps_nsat = buf.get_u8()?;
17010 let tmp = buf.get_u8()?;
17011 __struct.gps_fix_type =
17012 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
17013 enum_type: "GpsFixType",
17014 value: tmp as u64,
17015 })?;
17016 __struct.battery_remaining = buf.get_u8()?;
17017 __struct.temperature = buf.get_i8()?;
17018 __struct.temperature_air = buf.get_i8()?;
17019 __struct.failsafe = buf.get_u8()?;
17020 __struct.wp_num = buf.get_u8()?;
17021 Ok(__struct)
17022 }
17023 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17024 let mut __tmp = BytesMut::new(bytes);
17025 #[allow(clippy::absurd_extreme_comparisons)]
17026 #[allow(unused_comparisons)]
17027 if __tmp.remaining() < Self::ENCODED_LEN {
17028 panic!(
17029 "buffer is too small (need {} bytes, but got {})",
17030 Self::ENCODED_LEN,
17031 __tmp.remaining(),
17032 )
17033 }
17034 __tmp.put_u32_le(self.custom_mode);
17035 __tmp.put_i32_le(self.latitude);
17036 __tmp.put_i32_le(self.longitude);
17037 __tmp.put_i16_le(self.roll);
17038 __tmp.put_i16_le(self.pitch);
17039 __tmp.put_u16_le(self.heading);
17040 __tmp.put_i16_le(self.heading_sp);
17041 __tmp.put_i16_le(self.altitude_amsl);
17042 __tmp.put_i16_le(self.altitude_sp);
17043 __tmp.put_u16_le(self.wp_distance);
17044 __tmp.put_u8(self.base_mode.bits() as u8);
17045 __tmp.put_u8(self.landed_state as u8);
17046 __tmp.put_i8(self.throttle);
17047 __tmp.put_u8(self.airspeed);
17048 __tmp.put_u8(self.airspeed_sp);
17049 __tmp.put_u8(self.groundspeed);
17050 __tmp.put_i8(self.climb_rate);
17051 __tmp.put_u8(self.gps_nsat);
17052 __tmp.put_u8(self.gps_fix_type as u8);
17053 __tmp.put_u8(self.battery_remaining);
17054 __tmp.put_i8(self.temperature);
17055 __tmp.put_i8(self.temperature_air);
17056 __tmp.put_u8(self.failsafe);
17057 __tmp.put_u8(self.wp_num);
17058 if matches!(version, MavlinkVersion::V2) {
17059 let len = __tmp.len();
17060 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17061 } else {
17062 __tmp.len()
17063 }
17064 }
17065}
17066#[doc = "Message appropriate for high latency connections like Iridium (version 2)."]
17067#[doc = ""]
17068#[doc = "ID: 235"]
17069#[derive(Debug, Clone, PartialEq)]
17070#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17071#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17072#[cfg_attr(feature = "ts", derive(TS))]
17073#[cfg_attr(feature = "ts", ts(export))]
17074pub struct HIGH_LATENCY2_DATA {
17075 #[doc = "Timestamp (milliseconds since boot or Unix epoch)"]
17076 pub timestamp: u32,
17077 #[doc = "Latitude"]
17078 pub latitude: i32,
17079 #[doc = "Longitude"]
17080 pub longitude: i32,
17081 #[doc = "A bitfield for use for autopilot-specific flags (2 byte version)."]
17082 pub custom_mode: u16,
17083 #[doc = "Altitude above mean sea level"]
17084 pub altitude: i16,
17085 #[doc = "Altitude setpoint"]
17086 pub target_altitude: i16,
17087 #[doc = "Distance to target waypoint or position"]
17088 pub target_distance: u16,
17089 #[doc = "Current waypoint number"]
17090 pub wp_num: u16,
17091 #[doc = "Bitmap of failure flags."]
17092 pub failure_flags: HlFailureFlag,
17093 #[doc = "Type of the MAV (quadrotor, helicopter, etc.)"]
17094 pub mavtype: MavType,
17095 #[doc = "Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers."]
17096 pub autopilot: MavAutopilot,
17097 #[doc = "Heading"]
17098 pub heading: u8,
17099 #[doc = "Heading setpoint"]
17100 pub target_heading: u8,
17101 #[doc = "Throttle"]
17102 pub throttle: u8,
17103 #[doc = "Airspeed"]
17104 pub airspeed: u8,
17105 #[doc = "Airspeed setpoint"]
17106 pub airspeed_sp: u8,
17107 #[doc = "Groundspeed"]
17108 pub groundspeed: u8,
17109 #[doc = "Windspeed"]
17110 pub windspeed: u8,
17111 #[doc = "Wind heading"]
17112 pub wind_heading: u8,
17113 #[doc = "Maximum error horizontal position since last message"]
17114 pub eph: u8,
17115 #[doc = "Maximum error vertical position since last message"]
17116 pub epv: u8,
17117 #[doc = "Air temperature"]
17118 pub temperature_air: i8,
17119 #[doc = "Maximum climb rate magnitude since last message"]
17120 pub climb_rate: i8,
17121 #[doc = "Battery level (-1 if field not provided)."]
17122 pub battery: i8,
17123 #[doc = "Field for custom payload."]
17124 pub custom0: i8,
17125 #[doc = "Field for custom payload."]
17126 pub custom1: i8,
17127 #[doc = "Field for custom payload."]
17128 pub custom2: i8,
17129}
17130impl HIGH_LATENCY2_DATA {
17131 pub const ENCODED_LEN: usize = 42usize;
17132 pub const DEFAULT: Self = Self {
17133 timestamp: 0_u32,
17134 latitude: 0_i32,
17135 longitude: 0_i32,
17136 custom_mode: 0_u16,
17137 altitude: 0_i16,
17138 target_altitude: 0_i16,
17139 target_distance: 0_u16,
17140 wp_num: 0_u16,
17141 failure_flags: HlFailureFlag::DEFAULT,
17142 mavtype: MavType::DEFAULT,
17143 autopilot: MavAutopilot::DEFAULT,
17144 heading: 0_u8,
17145 target_heading: 0_u8,
17146 throttle: 0_u8,
17147 airspeed: 0_u8,
17148 airspeed_sp: 0_u8,
17149 groundspeed: 0_u8,
17150 windspeed: 0_u8,
17151 wind_heading: 0_u8,
17152 eph: 0_u8,
17153 epv: 0_u8,
17154 temperature_air: 0_i8,
17155 climb_rate: 0_i8,
17156 battery: 0_i8,
17157 custom0: 0_i8,
17158 custom1: 0_i8,
17159 custom2: 0_i8,
17160 };
17161 #[cfg(feature = "arbitrary")]
17162 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17163 use arbitrary::{Arbitrary, Unstructured};
17164 let mut buf = [0u8; 1024];
17165 rng.fill_bytes(&mut buf);
17166 let mut unstructured = Unstructured::new(&buf);
17167 Self::arbitrary(&mut unstructured).unwrap_or_default()
17168 }
17169}
17170impl Default for HIGH_LATENCY2_DATA {
17171 fn default() -> Self {
17172 Self::DEFAULT.clone()
17173 }
17174}
17175impl MessageData for HIGH_LATENCY2_DATA {
17176 type Message = MavMessage;
17177 const ID: u32 = 235u32;
17178 const NAME: &'static str = "HIGH_LATENCY2";
17179 const EXTRA_CRC: u8 = 179u8;
17180 const ENCODED_LEN: usize = 42usize;
17181 fn deser(
17182 _version: MavlinkVersion,
17183 __input: &[u8],
17184 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17185 let avail_len = __input.len();
17186 let mut payload_buf = [0; Self::ENCODED_LEN];
17187 let mut buf = if avail_len < Self::ENCODED_LEN {
17188 payload_buf[0..avail_len].copy_from_slice(__input);
17189 Bytes::new(&payload_buf)
17190 } else {
17191 Bytes::new(__input)
17192 };
17193 let mut __struct = Self::default();
17194 __struct.timestamp = buf.get_u32_le()?;
17195 __struct.latitude = buf.get_i32_le()?;
17196 __struct.longitude = buf.get_i32_le()?;
17197 __struct.custom_mode = buf.get_u16_le()?;
17198 __struct.altitude = buf.get_i16_le()?;
17199 __struct.target_altitude = buf.get_i16_le()?;
17200 __struct.target_distance = buf.get_u16_le()?;
17201 __struct.wp_num = buf.get_u16_le()?;
17202 let tmp = buf.get_u16_le()?;
17203 __struct.failure_flags = HlFailureFlag::from_bits(tmp as <HlFailureFlag as Flags>::Bits)
17204 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
17205 flag_type: "HlFailureFlag",
17206 value: tmp as u64,
17207 })?;
17208 let tmp = buf.get_u8()?;
17209 __struct.mavtype =
17210 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
17211 enum_type: "MavType",
17212 value: tmp as u64,
17213 })?;
17214 let tmp = buf.get_u8()?;
17215 __struct.autopilot =
17216 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
17217 enum_type: "MavAutopilot",
17218 value: tmp as u64,
17219 })?;
17220 __struct.heading = buf.get_u8()?;
17221 __struct.target_heading = buf.get_u8()?;
17222 __struct.throttle = buf.get_u8()?;
17223 __struct.airspeed = buf.get_u8()?;
17224 __struct.airspeed_sp = buf.get_u8()?;
17225 __struct.groundspeed = buf.get_u8()?;
17226 __struct.windspeed = buf.get_u8()?;
17227 __struct.wind_heading = buf.get_u8()?;
17228 __struct.eph = buf.get_u8()?;
17229 __struct.epv = buf.get_u8()?;
17230 __struct.temperature_air = buf.get_i8()?;
17231 __struct.climb_rate = buf.get_i8()?;
17232 __struct.battery = buf.get_i8()?;
17233 __struct.custom0 = buf.get_i8()?;
17234 __struct.custom1 = buf.get_i8()?;
17235 __struct.custom2 = buf.get_i8()?;
17236 Ok(__struct)
17237 }
17238 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17239 let mut __tmp = BytesMut::new(bytes);
17240 #[allow(clippy::absurd_extreme_comparisons)]
17241 #[allow(unused_comparisons)]
17242 if __tmp.remaining() < Self::ENCODED_LEN {
17243 panic!(
17244 "buffer is too small (need {} bytes, but got {})",
17245 Self::ENCODED_LEN,
17246 __tmp.remaining(),
17247 )
17248 }
17249 __tmp.put_u32_le(self.timestamp);
17250 __tmp.put_i32_le(self.latitude);
17251 __tmp.put_i32_le(self.longitude);
17252 __tmp.put_u16_le(self.custom_mode);
17253 __tmp.put_i16_le(self.altitude);
17254 __tmp.put_i16_le(self.target_altitude);
17255 __tmp.put_u16_le(self.target_distance);
17256 __tmp.put_u16_le(self.wp_num);
17257 __tmp.put_u16_le(self.failure_flags.bits() as u16);
17258 __tmp.put_u8(self.mavtype as u8);
17259 __tmp.put_u8(self.autopilot as u8);
17260 __tmp.put_u8(self.heading);
17261 __tmp.put_u8(self.target_heading);
17262 __tmp.put_u8(self.throttle);
17263 __tmp.put_u8(self.airspeed);
17264 __tmp.put_u8(self.airspeed_sp);
17265 __tmp.put_u8(self.groundspeed);
17266 __tmp.put_u8(self.windspeed);
17267 __tmp.put_u8(self.wind_heading);
17268 __tmp.put_u8(self.eph);
17269 __tmp.put_u8(self.epv);
17270 __tmp.put_i8(self.temperature_air);
17271 __tmp.put_i8(self.climb_rate);
17272 __tmp.put_i8(self.battery);
17273 __tmp.put_i8(self.custom0);
17274 __tmp.put_i8(self.custom1);
17275 __tmp.put_i8(self.custom2);
17276 if matches!(version, MavlinkVersion::V2) {
17277 let len = __tmp.len();
17278 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17279 } else {
17280 __tmp.len()
17281 }
17282 }
17283}
17284#[doc = "Sent from autopilot to simulation. Hardware in the loop control outputs. Alternative to HIL_CONTROLS."]
17285#[doc = ""]
17286#[doc = "ID: 93"]
17287#[derive(Debug, Clone, PartialEq)]
17288#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17289#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17290#[cfg_attr(feature = "ts", derive(TS))]
17291#[cfg_attr(feature = "ts", ts(export))]
17292pub struct HIL_ACTUATOR_CONTROLS_DATA {
17293 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
17294 pub time_usec: u64,
17295 #[doc = "Flags bitmask."]
17296 pub flags: HilActuatorControlsFlags,
17297 #[doc = "Control outputs -1 .. 1. Channel assignment depends on the simulated hardware."]
17298 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17299 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
17300 pub controls: [f32; 16],
17301 #[doc = "System mode. Includes arming state."]
17302 pub mode: MavModeFlag,
17303}
17304impl HIL_ACTUATOR_CONTROLS_DATA {
17305 pub const ENCODED_LEN: usize = 81usize;
17306 pub const DEFAULT: Self = Self {
17307 time_usec: 0_u64,
17308 flags: HilActuatorControlsFlags::DEFAULT,
17309 controls: [0.0_f32; 16usize],
17310 mode: MavModeFlag::DEFAULT,
17311 };
17312 #[cfg(feature = "arbitrary")]
17313 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17314 use arbitrary::{Arbitrary, Unstructured};
17315 let mut buf = [0u8; 1024];
17316 rng.fill_bytes(&mut buf);
17317 let mut unstructured = Unstructured::new(&buf);
17318 Self::arbitrary(&mut unstructured).unwrap_or_default()
17319 }
17320}
17321impl Default for HIL_ACTUATOR_CONTROLS_DATA {
17322 fn default() -> Self {
17323 Self::DEFAULT.clone()
17324 }
17325}
17326impl MessageData for HIL_ACTUATOR_CONTROLS_DATA {
17327 type Message = MavMessage;
17328 const ID: u32 = 93u32;
17329 const NAME: &'static str = "HIL_ACTUATOR_CONTROLS";
17330 const EXTRA_CRC: u8 = 47u8;
17331 const ENCODED_LEN: usize = 81usize;
17332 fn deser(
17333 _version: MavlinkVersion,
17334 __input: &[u8],
17335 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17336 let avail_len = __input.len();
17337 let mut payload_buf = [0; Self::ENCODED_LEN];
17338 let mut buf = if avail_len < Self::ENCODED_LEN {
17339 payload_buf[0..avail_len].copy_from_slice(__input);
17340 Bytes::new(&payload_buf)
17341 } else {
17342 Bytes::new(__input)
17343 };
17344 let mut __struct = Self::default();
17345 __struct.time_usec = buf.get_u64_le()?;
17346 let tmp = buf.get_u64_le()?;
17347 __struct.flags =
17348 HilActuatorControlsFlags::from_bits(tmp as <HilActuatorControlsFlags as Flags>::Bits)
17349 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
17350 flag_type: "HilActuatorControlsFlags",
17351 value: tmp as u64,
17352 })?;
17353 for v in &mut __struct.controls {
17354 let val = buf.get_f32_le()?;
17355 *v = val;
17356 }
17357 let tmp = buf.get_u8()?;
17358 __struct.mode = MavModeFlag::from_bits(tmp as <MavModeFlag as Flags>::Bits).ok_or(
17359 ::mavlink_core::error::ParserError::InvalidFlag {
17360 flag_type: "MavModeFlag",
17361 value: tmp as u64,
17362 },
17363 )?;
17364 Ok(__struct)
17365 }
17366 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17367 let mut __tmp = BytesMut::new(bytes);
17368 #[allow(clippy::absurd_extreme_comparisons)]
17369 #[allow(unused_comparisons)]
17370 if __tmp.remaining() < Self::ENCODED_LEN {
17371 panic!(
17372 "buffer is too small (need {} bytes, but got {})",
17373 Self::ENCODED_LEN,
17374 __tmp.remaining(),
17375 )
17376 }
17377 __tmp.put_u64_le(self.time_usec);
17378 __tmp.put_u64_le(self.flags.bits() as u64);
17379 for val in &self.controls {
17380 __tmp.put_f32_le(*val);
17381 }
17382 __tmp.put_u8(self.mode.bits() as u8);
17383 if matches!(version, MavlinkVersion::V2) {
17384 let len = __tmp.len();
17385 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17386 } else {
17387 __tmp.len()
17388 }
17389 }
17390}
17391#[doc = "Sent from autopilot to simulation. Hardware in the loop control outputs. Alternative to HIL_ACTUATOR_CONTROLS."]
17392#[doc = ""]
17393#[doc = "ID: 91"]
17394#[derive(Debug, Clone, PartialEq)]
17395#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17396#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17397#[cfg_attr(feature = "ts", derive(TS))]
17398#[cfg_attr(feature = "ts", ts(export))]
17399pub struct HIL_CONTROLS_DATA {
17400 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
17401 pub time_usec: u64,
17402 #[doc = "Control output -1 .. 1"]
17403 pub roll_ailerons: f32,
17404 #[doc = "Control output -1 .. 1"]
17405 pub pitch_elevator: f32,
17406 #[doc = "Control output -1 .. 1"]
17407 pub yaw_rudder: f32,
17408 #[doc = "Throttle 0 .. 1"]
17409 pub throttle: f32,
17410 #[doc = "Aux 1, -1 .. 1"]
17411 pub aux1: f32,
17412 #[doc = "Aux 2, -1 .. 1"]
17413 pub aux2: f32,
17414 #[doc = "Aux 3, -1 .. 1"]
17415 pub aux3: f32,
17416 #[doc = "Aux 4, -1 .. 1"]
17417 pub aux4: f32,
17418 #[doc = "System mode."]
17419 pub mode: MavMode,
17420 #[doc = "Navigation mode (MAV_NAV_MODE)"]
17421 pub nav_mode: u8,
17422}
17423impl HIL_CONTROLS_DATA {
17424 pub const ENCODED_LEN: usize = 42usize;
17425 pub const DEFAULT: Self = Self {
17426 time_usec: 0_u64,
17427 roll_ailerons: 0.0_f32,
17428 pitch_elevator: 0.0_f32,
17429 yaw_rudder: 0.0_f32,
17430 throttle: 0.0_f32,
17431 aux1: 0.0_f32,
17432 aux2: 0.0_f32,
17433 aux3: 0.0_f32,
17434 aux4: 0.0_f32,
17435 mode: MavMode::DEFAULT,
17436 nav_mode: 0_u8,
17437 };
17438 #[cfg(feature = "arbitrary")]
17439 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17440 use arbitrary::{Arbitrary, Unstructured};
17441 let mut buf = [0u8; 1024];
17442 rng.fill_bytes(&mut buf);
17443 let mut unstructured = Unstructured::new(&buf);
17444 Self::arbitrary(&mut unstructured).unwrap_or_default()
17445 }
17446}
17447impl Default for HIL_CONTROLS_DATA {
17448 fn default() -> Self {
17449 Self::DEFAULT.clone()
17450 }
17451}
17452impl MessageData for HIL_CONTROLS_DATA {
17453 type Message = MavMessage;
17454 const ID: u32 = 91u32;
17455 const NAME: &'static str = "HIL_CONTROLS";
17456 const EXTRA_CRC: u8 = 63u8;
17457 const ENCODED_LEN: usize = 42usize;
17458 fn deser(
17459 _version: MavlinkVersion,
17460 __input: &[u8],
17461 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17462 let avail_len = __input.len();
17463 let mut payload_buf = [0; Self::ENCODED_LEN];
17464 let mut buf = if avail_len < Self::ENCODED_LEN {
17465 payload_buf[0..avail_len].copy_from_slice(__input);
17466 Bytes::new(&payload_buf)
17467 } else {
17468 Bytes::new(__input)
17469 };
17470 let mut __struct = Self::default();
17471 __struct.time_usec = buf.get_u64_le()?;
17472 __struct.roll_ailerons = buf.get_f32_le()?;
17473 __struct.pitch_elevator = buf.get_f32_le()?;
17474 __struct.yaw_rudder = buf.get_f32_le()?;
17475 __struct.throttle = buf.get_f32_le()?;
17476 __struct.aux1 = buf.get_f32_le()?;
17477 __struct.aux2 = buf.get_f32_le()?;
17478 __struct.aux3 = buf.get_f32_le()?;
17479 __struct.aux4 = buf.get_f32_le()?;
17480 let tmp = buf.get_u8()?;
17481 __struct.mode =
17482 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
17483 enum_type: "MavMode",
17484 value: tmp as u64,
17485 })?;
17486 __struct.nav_mode = buf.get_u8()?;
17487 Ok(__struct)
17488 }
17489 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17490 let mut __tmp = BytesMut::new(bytes);
17491 #[allow(clippy::absurd_extreme_comparisons)]
17492 #[allow(unused_comparisons)]
17493 if __tmp.remaining() < Self::ENCODED_LEN {
17494 panic!(
17495 "buffer is too small (need {} bytes, but got {})",
17496 Self::ENCODED_LEN,
17497 __tmp.remaining(),
17498 )
17499 }
17500 __tmp.put_u64_le(self.time_usec);
17501 __tmp.put_f32_le(self.roll_ailerons);
17502 __tmp.put_f32_le(self.pitch_elevator);
17503 __tmp.put_f32_le(self.yaw_rudder);
17504 __tmp.put_f32_le(self.throttle);
17505 __tmp.put_f32_le(self.aux1);
17506 __tmp.put_f32_le(self.aux2);
17507 __tmp.put_f32_le(self.aux3);
17508 __tmp.put_f32_le(self.aux4);
17509 __tmp.put_u8(self.mode as u8);
17510 __tmp.put_u8(self.nav_mode);
17511 if matches!(version, MavlinkVersion::V2) {
17512 let len = __tmp.len();
17513 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17514 } else {
17515 __tmp.len()
17516 }
17517 }
17518}
17519#[doc = "The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION_INT for the global position estimate."]
17520#[doc = ""]
17521#[doc = "ID: 113"]
17522#[derive(Debug, Clone, PartialEq)]
17523#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17524#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17525#[cfg_attr(feature = "ts", derive(TS))]
17526#[cfg_attr(feature = "ts", ts(export))]
17527pub struct HIL_GPS_DATA {
17528 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
17529 pub time_usec: u64,
17530 #[doc = "Latitude (WGS84)"]
17531 pub lat: i32,
17532 #[doc = "Longitude (WGS84)"]
17533 pub lon: i32,
17534 #[doc = "Altitude (MSL). Positive for up."]
17535 pub alt: i32,
17536 #[doc = "GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
17537 pub eph: u16,
17538 #[doc = "GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
17539 pub epv: u16,
17540 #[doc = "GPS ground speed. If unknown, set to: UINT16_MAX"]
17541 pub vel: u16,
17542 #[doc = "GPS velocity in north direction in earth-fixed NED frame"]
17543 pub vn: i16,
17544 #[doc = "GPS velocity in east direction in earth-fixed NED frame"]
17545 pub ve: i16,
17546 #[doc = "GPS velocity in down direction in earth-fixed NED frame"]
17547 pub vd: i16,
17548 #[doc = "Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX"]
17549 pub cog: u16,
17550 #[doc = "0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix."]
17551 pub fix_type: u8,
17552 #[doc = "Number of satellites visible. If unknown, set to UINT8_MAX"]
17553 pub satellites_visible: u8,
17554 #[doc = "GPS ID (zero indexed). Used for multiple GPS inputs"]
17555 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
17556 pub id: u8,
17557 #[doc = "Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north"]
17558 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
17559 pub yaw: u16,
17560}
17561impl HIL_GPS_DATA {
17562 pub const ENCODED_LEN: usize = 39usize;
17563 pub const DEFAULT: Self = Self {
17564 time_usec: 0_u64,
17565 lat: 0_i32,
17566 lon: 0_i32,
17567 alt: 0_i32,
17568 eph: 0_u16,
17569 epv: 0_u16,
17570 vel: 0_u16,
17571 vn: 0_i16,
17572 ve: 0_i16,
17573 vd: 0_i16,
17574 cog: 0_u16,
17575 fix_type: 0_u8,
17576 satellites_visible: 0_u8,
17577 id: 0_u8,
17578 yaw: 0_u16,
17579 };
17580 #[cfg(feature = "arbitrary")]
17581 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17582 use arbitrary::{Arbitrary, Unstructured};
17583 let mut buf = [0u8; 1024];
17584 rng.fill_bytes(&mut buf);
17585 let mut unstructured = Unstructured::new(&buf);
17586 Self::arbitrary(&mut unstructured).unwrap_or_default()
17587 }
17588}
17589impl Default for HIL_GPS_DATA {
17590 fn default() -> Self {
17591 Self::DEFAULT.clone()
17592 }
17593}
17594impl MessageData for HIL_GPS_DATA {
17595 type Message = MavMessage;
17596 const ID: u32 = 113u32;
17597 const NAME: &'static str = "HIL_GPS";
17598 const EXTRA_CRC: u8 = 124u8;
17599 const ENCODED_LEN: usize = 39usize;
17600 fn deser(
17601 _version: MavlinkVersion,
17602 __input: &[u8],
17603 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17604 let avail_len = __input.len();
17605 let mut payload_buf = [0; Self::ENCODED_LEN];
17606 let mut buf = if avail_len < Self::ENCODED_LEN {
17607 payload_buf[0..avail_len].copy_from_slice(__input);
17608 Bytes::new(&payload_buf)
17609 } else {
17610 Bytes::new(__input)
17611 };
17612 let mut __struct = Self::default();
17613 __struct.time_usec = buf.get_u64_le()?;
17614 __struct.lat = buf.get_i32_le()?;
17615 __struct.lon = buf.get_i32_le()?;
17616 __struct.alt = buf.get_i32_le()?;
17617 __struct.eph = buf.get_u16_le()?;
17618 __struct.epv = buf.get_u16_le()?;
17619 __struct.vel = buf.get_u16_le()?;
17620 __struct.vn = buf.get_i16_le()?;
17621 __struct.ve = buf.get_i16_le()?;
17622 __struct.vd = buf.get_i16_le()?;
17623 __struct.cog = buf.get_u16_le()?;
17624 __struct.fix_type = buf.get_u8()?;
17625 __struct.satellites_visible = buf.get_u8()?;
17626 __struct.id = buf.get_u8()?;
17627 __struct.yaw = buf.get_u16_le()?;
17628 Ok(__struct)
17629 }
17630 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17631 let mut __tmp = BytesMut::new(bytes);
17632 #[allow(clippy::absurd_extreme_comparisons)]
17633 #[allow(unused_comparisons)]
17634 if __tmp.remaining() < Self::ENCODED_LEN {
17635 panic!(
17636 "buffer is too small (need {} bytes, but got {})",
17637 Self::ENCODED_LEN,
17638 __tmp.remaining(),
17639 )
17640 }
17641 __tmp.put_u64_le(self.time_usec);
17642 __tmp.put_i32_le(self.lat);
17643 __tmp.put_i32_le(self.lon);
17644 __tmp.put_i32_le(self.alt);
17645 __tmp.put_u16_le(self.eph);
17646 __tmp.put_u16_le(self.epv);
17647 __tmp.put_u16_le(self.vel);
17648 __tmp.put_i16_le(self.vn);
17649 __tmp.put_i16_le(self.ve);
17650 __tmp.put_i16_le(self.vd);
17651 __tmp.put_u16_le(self.cog);
17652 __tmp.put_u8(self.fix_type);
17653 __tmp.put_u8(self.satellites_visible);
17654 if matches!(version, MavlinkVersion::V2) {
17655 __tmp.put_u8(self.id);
17656 __tmp.put_u16_le(self.yaw);
17657 let len = __tmp.len();
17658 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17659 } else {
17660 __tmp.len()
17661 }
17662 }
17663}
17664#[doc = "Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical mouse sensor)."]
17665#[doc = ""]
17666#[doc = "ID: 114"]
17667#[derive(Debug, Clone, PartialEq)]
17668#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17669#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17670#[cfg_attr(feature = "ts", derive(TS))]
17671#[cfg_attr(feature = "ts", ts(export))]
17672pub struct HIL_OPTICAL_FLOW_DATA {
17673 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
17674 pub time_usec: u64,
17675 #[doc = "Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the."]
17676 pub integration_time_us: u32,
17677 #[doc = "Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)"]
17678 pub integrated_x: f32,
17679 #[doc = "Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)"]
17680 pub integrated_y: f32,
17681 #[doc = "RH rotation around X axis"]
17682 pub integrated_xgyro: f32,
17683 #[doc = "RH rotation around Y axis"]
17684 pub integrated_ygyro: f32,
17685 #[doc = "RH rotation around Z axis"]
17686 pub integrated_zgyro: f32,
17687 #[doc = "Time since the distance was sampled."]
17688 pub time_delta_distance_us: u32,
17689 #[doc = "Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance."]
17690 pub distance: f32,
17691 #[doc = "Temperature"]
17692 pub temperature: i16,
17693 #[doc = "Sensor ID"]
17694 pub sensor_id: u8,
17695 #[doc = "Optical flow quality / confidence. 0: no valid flow, 255: maximum quality"]
17696 pub quality: u8,
17697}
17698impl HIL_OPTICAL_FLOW_DATA {
17699 pub const ENCODED_LEN: usize = 44usize;
17700 pub const DEFAULT: Self = Self {
17701 time_usec: 0_u64,
17702 integration_time_us: 0_u32,
17703 integrated_x: 0.0_f32,
17704 integrated_y: 0.0_f32,
17705 integrated_xgyro: 0.0_f32,
17706 integrated_ygyro: 0.0_f32,
17707 integrated_zgyro: 0.0_f32,
17708 time_delta_distance_us: 0_u32,
17709 distance: 0.0_f32,
17710 temperature: 0_i16,
17711 sensor_id: 0_u8,
17712 quality: 0_u8,
17713 };
17714 #[cfg(feature = "arbitrary")]
17715 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17716 use arbitrary::{Arbitrary, Unstructured};
17717 let mut buf = [0u8; 1024];
17718 rng.fill_bytes(&mut buf);
17719 let mut unstructured = Unstructured::new(&buf);
17720 Self::arbitrary(&mut unstructured).unwrap_or_default()
17721 }
17722}
17723impl Default for HIL_OPTICAL_FLOW_DATA {
17724 fn default() -> Self {
17725 Self::DEFAULT.clone()
17726 }
17727}
17728impl MessageData for HIL_OPTICAL_FLOW_DATA {
17729 type Message = MavMessage;
17730 const ID: u32 = 114u32;
17731 const NAME: &'static str = "HIL_OPTICAL_FLOW";
17732 const EXTRA_CRC: u8 = 237u8;
17733 const ENCODED_LEN: usize = 44usize;
17734 fn deser(
17735 _version: MavlinkVersion,
17736 __input: &[u8],
17737 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17738 let avail_len = __input.len();
17739 let mut payload_buf = [0; Self::ENCODED_LEN];
17740 let mut buf = if avail_len < Self::ENCODED_LEN {
17741 payload_buf[0..avail_len].copy_from_slice(__input);
17742 Bytes::new(&payload_buf)
17743 } else {
17744 Bytes::new(__input)
17745 };
17746 let mut __struct = Self::default();
17747 __struct.time_usec = buf.get_u64_le()?;
17748 __struct.integration_time_us = buf.get_u32_le()?;
17749 __struct.integrated_x = buf.get_f32_le()?;
17750 __struct.integrated_y = buf.get_f32_le()?;
17751 __struct.integrated_xgyro = buf.get_f32_le()?;
17752 __struct.integrated_ygyro = buf.get_f32_le()?;
17753 __struct.integrated_zgyro = buf.get_f32_le()?;
17754 __struct.time_delta_distance_us = buf.get_u32_le()?;
17755 __struct.distance = buf.get_f32_le()?;
17756 __struct.temperature = buf.get_i16_le()?;
17757 __struct.sensor_id = buf.get_u8()?;
17758 __struct.quality = buf.get_u8()?;
17759 Ok(__struct)
17760 }
17761 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17762 let mut __tmp = BytesMut::new(bytes);
17763 #[allow(clippy::absurd_extreme_comparisons)]
17764 #[allow(unused_comparisons)]
17765 if __tmp.remaining() < Self::ENCODED_LEN {
17766 panic!(
17767 "buffer is too small (need {} bytes, but got {})",
17768 Self::ENCODED_LEN,
17769 __tmp.remaining(),
17770 )
17771 }
17772 __tmp.put_u64_le(self.time_usec);
17773 __tmp.put_u32_le(self.integration_time_us);
17774 __tmp.put_f32_le(self.integrated_x);
17775 __tmp.put_f32_le(self.integrated_y);
17776 __tmp.put_f32_le(self.integrated_xgyro);
17777 __tmp.put_f32_le(self.integrated_ygyro);
17778 __tmp.put_f32_le(self.integrated_zgyro);
17779 __tmp.put_u32_le(self.time_delta_distance_us);
17780 __tmp.put_f32_le(self.distance);
17781 __tmp.put_i16_le(self.temperature);
17782 __tmp.put_u8(self.sensor_id);
17783 __tmp.put_u8(self.quality);
17784 if matches!(version, MavlinkVersion::V2) {
17785 let len = __tmp.len();
17786 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17787 } else {
17788 __tmp.len()
17789 }
17790 }
17791}
17792#[doc = "Sent from simulation to autopilot. The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification."]
17793#[doc = ""]
17794#[doc = "ID: 92"]
17795#[derive(Debug, Clone, PartialEq)]
17796#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17797#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17798#[cfg_attr(feature = "ts", derive(TS))]
17799#[cfg_attr(feature = "ts", ts(export))]
17800pub struct HIL_RC_INPUTS_RAW_DATA {
17801 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
17802 pub time_usec: u64,
17803 #[doc = "RC channel 1 value"]
17804 pub chan1_raw: u16,
17805 #[doc = "RC channel 2 value"]
17806 pub chan2_raw: u16,
17807 #[doc = "RC channel 3 value"]
17808 pub chan3_raw: u16,
17809 #[doc = "RC channel 4 value"]
17810 pub chan4_raw: u16,
17811 #[doc = "RC channel 5 value"]
17812 pub chan5_raw: u16,
17813 #[doc = "RC channel 6 value"]
17814 pub chan6_raw: u16,
17815 #[doc = "RC channel 7 value"]
17816 pub chan7_raw: u16,
17817 #[doc = "RC channel 8 value"]
17818 pub chan8_raw: u16,
17819 #[doc = "RC channel 9 value"]
17820 pub chan9_raw: u16,
17821 #[doc = "RC channel 10 value"]
17822 pub chan10_raw: u16,
17823 #[doc = "RC channel 11 value"]
17824 pub chan11_raw: u16,
17825 #[doc = "RC channel 12 value"]
17826 pub chan12_raw: u16,
17827 #[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
17828 pub rssi: u8,
17829}
17830impl HIL_RC_INPUTS_RAW_DATA {
17831 pub const ENCODED_LEN: usize = 33usize;
17832 pub const DEFAULT: Self = Self {
17833 time_usec: 0_u64,
17834 chan1_raw: 0_u16,
17835 chan2_raw: 0_u16,
17836 chan3_raw: 0_u16,
17837 chan4_raw: 0_u16,
17838 chan5_raw: 0_u16,
17839 chan6_raw: 0_u16,
17840 chan7_raw: 0_u16,
17841 chan8_raw: 0_u16,
17842 chan9_raw: 0_u16,
17843 chan10_raw: 0_u16,
17844 chan11_raw: 0_u16,
17845 chan12_raw: 0_u16,
17846 rssi: 0_u8,
17847 };
17848 #[cfg(feature = "arbitrary")]
17849 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17850 use arbitrary::{Arbitrary, Unstructured};
17851 let mut buf = [0u8; 1024];
17852 rng.fill_bytes(&mut buf);
17853 let mut unstructured = Unstructured::new(&buf);
17854 Self::arbitrary(&mut unstructured).unwrap_or_default()
17855 }
17856}
17857impl Default for HIL_RC_INPUTS_RAW_DATA {
17858 fn default() -> Self {
17859 Self::DEFAULT.clone()
17860 }
17861}
17862impl MessageData for HIL_RC_INPUTS_RAW_DATA {
17863 type Message = MavMessage;
17864 const ID: u32 = 92u32;
17865 const NAME: &'static str = "HIL_RC_INPUTS_RAW";
17866 const EXTRA_CRC: u8 = 54u8;
17867 const ENCODED_LEN: usize = 33usize;
17868 fn deser(
17869 _version: MavlinkVersion,
17870 __input: &[u8],
17871 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17872 let avail_len = __input.len();
17873 let mut payload_buf = [0; Self::ENCODED_LEN];
17874 let mut buf = if avail_len < Self::ENCODED_LEN {
17875 payload_buf[0..avail_len].copy_from_slice(__input);
17876 Bytes::new(&payload_buf)
17877 } else {
17878 Bytes::new(__input)
17879 };
17880 let mut __struct = Self::default();
17881 __struct.time_usec = buf.get_u64_le()?;
17882 __struct.chan1_raw = buf.get_u16_le()?;
17883 __struct.chan2_raw = buf.get_u16_le()?;
17884 __struct.chan3_raw = buf.get_u16_le()?;
17885 __struct.chan4_raw = buf.get_u16_le()?;
17886 __struct.chan5_raw = buf.get_u16_le()?;
17887 __struct.chan6_raw = buf.get_u16_le()?;
17888 __struct.chan7_raw = buf.get_u16_le()?;
17889 __struct.chan8_raw = buf.get_u16_le()?;
17890 __struct.chan9_raw = buf.get_u16_le()?;
17891 __struct.chan10_raw = buf.get_u16_le()?;
17892 __struct.chan11_raw = buf.get_u16_le()?;
17893 __struct.chan12_raw = buf.get_u16_le()?;
17894 __struct.rssi = buf.get_u8()?;
17895 Ok(__struct)
17896 }
17897 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17898 let mut __tmp = BytesMut::new(bytes);
17899 #[allow(clippy::absurd_extreme_comparisons)]
17900 #[allow(unused_comparisons)]
17901 if __tmp.remaining() < Self::ENCODED_LEN {
17902 panic!(
17903 "buffer is too small (need {} bytes, but got {})",
17904 Self::ENCODED_LEN,
17905 __tmp.remaining(),
17906 )
17907 }
17908 __tmp.put_u64_le(self.time_usec);
17909 __tmp.put_u16_le(self.chan1_raw);
17910 __tmp.put_u16_le(self.chan2_raw);
17911 __tmp.put_u16_le(self.chan3_raw);
17912 __tmp.put_u16_le(self.chan4_raw);
17913 __tmp.put_u16_le(self.chan5_raw);
17914 __tmp.put_u16_le(self.chan6_raw);
17915 __tmp.put_u16_le(self.chan7_raw);
17916 __tmp.put_u16_le(self.chan8_raw);
17917 __tmp.put_u16_le(self.chan9_raw);
17918 __tmp.put_u16_le(self.chan10_raw);
17919 __tmp.put_u16_le(self.chan11_raw);
17920 __tmp.put_u16_le(self.chan12_raw);
17921 __tmp.put_u8(self.rssi);
17922 if matches!(version, MavlinkVersion::V2) {
17923 let len = __tmp.len();
17924 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17925 } else {
17926 __tmp.len()
17927 }
17928 }
17929}
17930#[doc = "The IMU readings in SI units in NED body frame."]
17931#[doc = ""]
17932#[doc = "ID: 107"]
17933#[derive(Debug, Clone, PartialEq)]
17934#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17935#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17936#[cfg_attr(feature = "ts", derive(TS))]
17937#[cfg_attr(feature = "ts", ts(export))]
17938pub struct HIL_SENSOR_DATA {
17939 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
17940 pub time_usec: u64,
17941 #[doc = "X acceleration"]
17942 pub xacc: f32,
17943 #[doc = "Y acceleration"]
17944 pub yacc: f32,
17945 #[doc = "Z acceleration"]
17946 pub zacc: f32,
17947 #[doc = "Angular speed around X axis in body frame"]
17948 pub xgyro: f32,
17949 #[doc = "Angular speed around Y axis in body frame"]
17950 pub ygyro: f32,
17951 #[doc = "Angular speed around Z axis in body frame"]
17952 pub zgyro: f32,
17953 #[doc = "X Magnetic field"]
17954 pub xmag: f32,
17955 #[doc = "Y Magnetic field"]
17956 pub ymag: f32,
17957 #[doc = "Z Magnetic field"]
17958 pub zmag: f32,
17959 #[doc = "Absolute pressure"]
17960 pub abs_pressure: f32,
17961 #[doc = "Differential pressure (airspeed)"]
17962 pub diff_pressure: f32,
17963 #[doc = "Altitude calculated from pressure"]
17964 pub pressure_alt: f32,
17965 #[doc = "Temperature"]
17966 pub temperature: f32,
17967 #[doc = "Bitmap for fields that have updated since last message"]
17968 pub fields_updated: HilSensorUpdatedFlags,
17969 #[doc = "Sensor ID (zero indexed). Used for multiple sensor inputs"]
17970 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
17971 pub id: u8,
17972}
17973impl HIL_SENSOR_DATA {
17974 pub const ENCODED_LEN: usize = 65usize;
17975 pub const DEFAULT: Self = Self {
17976 time_usec: 0_u64,
17977 xacc: 0.0_f32,
17978 yacc: 0.0_f32,
17979 zacc: 0.0_f32,
17980 xgyro: 0.0_f32,
17981 ygyro: 0.0_f32,
17982 zgyro: 0.0_f32,
17983 xmag: 0.0_f32,
17984 ymag: 0.0_f32,
17985 zmag: 0.0_f32,
17986 abs_pressure: 0.0_f32,
17987 diff_pressure: 0.0_f32,
17988 pressure_alt: 0.0_f32,
17989 temperature: 0.0_f32,
17990 fields_updated: HilSensorUpdatedFlags::DEFAULT,
17991 id: 0_u8,
17992 };
17993 #[cfg(feature = "arbitrary")]
17994 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17995 use arbitrary::{Arbitrary, Unstructured};
17996 let mut buf = [0u8; 1024];
17997 rng.fill_bytes(&mut buf);
17998 let mut unstructured = Unstructured::new(&buf);
17999 Self::arbitrary(&mut unstructured).unwrap_or_default()
18000 }
18001}
18002impl Default for HIL_SENSOR_DATA {
18003 fn default() -> Self {
18004 Self::DEFAULT.clone()
18005 }
18006}
18007impl MessageData for HIL_SENSOR_DATA {
18008 type Message = MavMessage;
18009 const ID: u32 = 107u32;
18010 const NAME: &'static str = "HIL_SENSOR";
18011 const EXTRA_CRC: u8 = 108u8;
18012 const ENCODED_LEN: usize = 65usize;
18013 fn deser(
18014 _version: MavlinkVersion,
18015 __input: &[u8],
18016 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18017 let avail_len = __input.len();
18018 let mut payload_buf = [0; Self::ENCODED_LEN];
18019 let mut buf = if avail_len < Self::ENCODED_LEN {
18020 payload_buf[0..avail_len].copy_from_slice(__input);
18021 Bytes::new(&payload_buf)
18022 } else {
18023 Bytes::new(__input)
18024 };
18025 let mut __struct = Self::default();
18026 __struct.time_usec = buf.get_u64_le()?;
18027 __struct.xacc = buf.get_f32_le()?;
18028 __struct.yacc = buf.get_f32_le()?;
18029 __struct.zacc = buf.get_f32_le()?;
18030 __struct.xgyro = buf.get_f32_le()?;
18031 __struct.ygyro = buf.get_f32_le()?;
18032 __struct.zgyro = buf.get_f32_le()?;
18033 __struct.xmag = buf.get_f32_le()?;
18034 __struct.ymag = buf.get_f32_le()?;
18035 __struct.zmag = buf.get_f32_le()?;
18036 __struct.abs_pressure = buf.get_f32_le()?;
18037 __struct.diff_pressure = buf.get_f32_le()?;
18038 __struct.pressure_alt = buf.get_f32_le()?;
18039 __struct.temperature = buf.get_f32_le()?;
18040 let tmp = buf.get_u32_le()?;
18041 __struct.fields_updated = HilSensorUpdatedFlags::from_bits(
18042 tmp as <HilSensorUpdatedFlags as Flags>::Bits,
18043 )
18044 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
18045 flag_type: "HilSensorUpdatedFlags",
18046 value: tmp as u64,
18047 })?;
18048 __struct.id = buf.get_u8()?;
18049 Ok(__struct)
18050 }
18051 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18052 let mut __tmp = BytesMut::new(bytes);
18053 #[allow(clippy::absurd_extreme_comparisons)]
18054 #[allow(unused_comparisons)]
18055 if __tmp.remaining() < Self::ENCODED_LEN {
18056 panic!(
18057 "buffer is too small (need {} bytes, but got {})",
18058 Self::ENCODED_LEN,
18059 __tmp.remaining(),
18060 )
18061 }
18062 __tmp.put_u64_le(self.time_usec);
18063 __tmp.put_f32_le(self.xacc);
18064 __tmp.put_f32_le(self.yacc);
18065 __tmp.put_f32_le(self.zacc);
18066 __tmp.put_f32_le(self.xgyro);
18067 __tmp.put_f32_le(self.ygyro);
18068 __tmp.put_f32_le(self.zgyro);
18069 __tmp.put_f32_le(self.xmag);
18070 __tmp.put_f32_le(self.ymag);
18071 __tmp.put_f32_le(self.zmag);
18072 __tmp.put_f32_le(self.abs_pressure);
18073 __tmp.put_f32_le(self.diff_pressure);
18074 __tmp.put_f32_le(self.pressure_alt);
18075 __tmp.put_f32_le(self.temperature);
18076 __tmp.put_u32_le(self.fields_updated.bits() as u32);
18077 if matches!(version, MavlinkVersion::V2) {
18078 __tmp.put_u8(self.id);
18079 let len = __tmp.len();
18080 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18081 } else {
18082 __tmp.len()
18083 }
18084 }
18085}
18086#[deprecated = "Suffers from missing airspeed fields and singularities due to Euler angles. See `HIL_STATE_QUATERNION` (Deprecated since 2013-07)"]
18087#[doc = "Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations."]
18088#[doc = ""]
18089#[doc = "ID: 90"]
18090#[derive(Debug, Clone, PartialEq)]
18091#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18092#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18093#[cfg_attr(feature = "ts", derive(TS))]
18094#[cfg_attr(feature = "ts", ts(export))]
18095pub struct HIL_STATE_DATA {
18096 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
18097 pub time_usec: u64,
18098 #[doc = "Roll angle"]
18099 pub roll: f32,
18100 #[doc = "Pitch angle"]
18101 pub pitch: f32,
18102 #[doc = "Yaw angle"]
18103 pub yaw: f32,
18104 #[doc = "Body frame roll / phi angular speed"]
18105 pub rollspeed: f32,
18106 #[doc = "Body frame pitch / theta angular speed"]
18107 pub pitchspeed: f32,
18108 #[doc = "Body frame yaw / psi angular speed"]
18109 pub yawspeed: f32,
18110 #[doc = "Latitude"]
18111 pub lat: i32,
18112 #[doc = "Longitude"]
18113 pub lon: i32,
18114 #[doc = "Altitude"]
18115 pub alt: i32,
18116 #[doc = "Ground X Speed (Latitude)"]
18117 pub vx: i16,
18118 #[doc = "Ground Y Speed (Longitude)"]
18119 pub vy: i16,
18120 #[doc = "Ground Z Speed (Altitude)"]
18121 pub vz: i16,
18122 #[doc = "X acceleration"]
18123 pub xacc: i16,
18124 #[doc = "Y acceleration"]
18125 pub yacc: i16,
18126 #[doc = "Z acceleration"]
18127 pub zacc: i16,
18128}
18129impl HIL_STATE_DATA {
18130 pub const ENCODED_LEN: usize = 56usize;
18131 pub const DEFAULT: Self = Self {
18132 time_usec: 0_u64,
18133 roll: 0.0_f32,
18134 pitch: 0.0_f32,
18135 yaw: 0.0_f32,
18136 rollspeed: 0.0_f32,
18137 pitchspeed: 0.0_f32,
18138 yawspeed: 0.0_f32,
18139 lat: 0_i32,
18140 lon: 0_i32,
18141 alt: 0_i32,
18142 vx: 0_i16,
18143 vy: 0_i16,
18144 vz: 0_i16,
18145 xacc: 0_i16,
18146 yacc: 0_i16,
18147 zacc: 0_i16,
18148 };
18149 #[cfg(feature = "arbitrary")]
18150 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18151 use arbitrary::{Arbitrary, Unstructured};
18152 let mut buf = [0u8; 1024];
18153 rng.fill_bytes(&mut buf);
18154 let mut unstructured = Unstructured::new(&buf);
18155 Self::arbitrary(&mut unstructured).unwrap_or_default()
18156 }
18157}
18158impl Default for HIL_STATE_DATA {
18159 fn default() -> Self {
18160 Self::DEFAULT.clone()
18161 }
18162}
18163impl MessageData for HIL_STATE_DATA {
18164 type Message = MavMessage;
18165 const ID: u32 = 90u32;
18166 const NAME: &'static str = "HIL_STATE";
18167 const EXTRA_CRC: u8 = 183u8;
18168 const ENCODED_LEN: usize = 56usize;
18169 fn deser(
18170 _version: MavlinkVersion,
18171 __input: &[u8],
18172 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18173 let avail_len = __input.len();
18174 let mut payload_buf = [0; Self::ENCODED_LEN];
18175 let mut buf = if avail_len < Self::ENCODED_LEN {
18176 payload_buf[0..avail_len].copy_from_slice(__input);
18177 Bytes::new(&payload_buf)
18178 } else {
18179 Bytes::new(__input)
18180 };
18181 let mut __struct = Self::default();
18182 __struct.time_usec = buf.get_u64_le()?;
18183 __struct.roll = buf.get_f32_le()?;
18184 __struct.pitch = buf.get_f32_le()?;
18185 __struct.yaw = buf.get_f32_le()?;
18186 __struct.rollspeed = buf.get_f32_le()?;
18187 __struct.pitchspeed = buf.get_f32_le()?;
18188 __struct.yawspeed = buf.get_f32_le()?;
18189 __struct.lat = buf.get_i32_le()?;
18190 __struct.lon = buf.get_i32_le()?;
18191 __struct.alt = buf.get_i32_le()?;
18192 __struct.vx = buf.get_i16_le()?;
18193 __struct.vy = buf.get_i16_le()?;
18194 __struct.vz = buf.get_i16_le()?;
18195 __struct.xacc = buf.get_i16_le()?;
18196 __struct.yacc = buf.get_i16_le()?;
18197 __struct.zacc = buf.get_i16_le()?;
18198 Ok(__struct)
18199 }
18200 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18201 let mut __tmp = BytesMut::new(bytes);
18202 #[allow(clippy::absurd_extreme_comparisons)]
18203 #[allow(unused_comparisons)]
18204 if __tmp.remaining() < Self::ENCODED_LEN {
18205 panic!(
18206 "buffer is too small (need {} bytes, but got {})",
18207 Self::ENCODED_LEN,
18208 __tmp.remaining(),
18209 )
18210 }
18211 __tmp.put_u64_le(self.time_usec);
18212 __tmp.put_f32_le(self.roll);
18213 __tmp.put_f32_le(self.pitch);
18214 __tmp.put_f32_le(self.yaw);
18215 __tmp.put_f32_le(self.rollspeed);
18216 __tmp.put_f32_le(self.pitchspeed);
18217 __tmp.put_f32_le(self.yawspeed);
18218 __tmp.put_i32_le(self.lat);
18219 __tmp.put_i32_le(self.lon);
18220 __tmp.put_i32_le(self.alt);
18221 __tmp.put_i16_le(self.vx);
18222 __tmp.put_i16_le(self.vy);
18223 __tmp.put_i16_le(self.vz);
18224 __tmp.put_i16_le(self.xacc);
18225 __tmp.put_i16_le(self.yacc);
18226 __tmp.put_i16_le(self.zacc);
18227 if matches!(version, MavlinkVersion::V2) {
18228 let len = __tmp.len();
18229 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18230 } else {
18231 __tmp.len()
18232 }
18233 }
18234}
18235#[doc = "Sent from simulation to autopilot, avoids in contrast to HIL_STATE singularities. This packet is useful for high throughput applications such as hardware in the loop simulations."]
18236#[doc = ""]
18237#[doc = "ID: 115"]
18238#[derive(Debug, Clone, PartialEq)]
18239#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18240#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18241#[cfg_attr(feature = "ts", derive(TS))]
18242#[cfg_attr(feature = "ts", ts(export))]
18243pub struct HIL_STATE_QUATERNION_DATA {
18244 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
18245 pub time_usec: u64,
18246 #[doc = "Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)"]
18247 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18248 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
18249 pub attitude_quaternion: [f32; 4],
18250 #[doc = "Body frame roll / phi angular speed"]
18251 pub rollspeed: f32,
18252 #[doc = "Body frame pitch / theta angular speed"]
18253 pub pitchspeed: f32,
18254 #[doc = "Body frame yaw / psi angular speed"]
18255 pub yawspeed: f32,
18256 #[doc = "Latitude"]
18257 pub lat: i32,
18258 #[doc = "Longitude"]
18259 pub lon: i32,
18260 #[doc = "Altitude"]
18261 pub alt: i32,
18262 #[doc = "Ground X Speed (Latitude)"]
18263 pub vx: i16,
18264 #[doc = "Ground Y Speed (Longitude)"]
18265 pub vy: i16,
18266 #[doc = "Ground Z Speed (Altitude)"]
18267 pub vz: i16,
18268 #[doc = "Indicated airspeed"]
18269 pub ind_airspeed: u16,
18270 #[doc = "True airspeed"]
18271 pub true_airspeed: u16,
18272 #[doc = "X acceleration"]
18273 pub xacc: i16,
18274 #[doc = "Y acceleration"]
18275 pub yacc: i16,
18276 #[doc = "Z acceleration"]
18277 pub zacc: i16,
18278}
18279impl HIL_STATE_QUATERNION_DATA {
18280 pub const ENCODED_LEN: usize = 64usize;
18281 pub const DEFAULT: Self = Self {
18282 time_usec: 0_u64,
18283 attitude_quaternion: [0.0_f32; 4usize],
18284 rollspeed: 0.0_f32,
18285 pitchspeed: 0.0_f32,
18286 yawspeed: 0.0_f32,
18287 lat: 0_i32,
18288 lon: 0_i32,
18289 alt: 0_i32,
18290 vx: 0_i16,
18291 vy: 0_i16,
18292 vz: 0_i16,
18293 ind_airspeed: 0_u16,
18294 true_airspeed: 0_u16,
18295 xacc: 0_i16,
18296 yacc: 0_i16,
18297 zacc: 0_i16,
18298 };
18299 #[cfg(feature = "arbitrary")]
18300 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18301 use arbitrary::{Arbitrary, Unstructured};
18302 let mut buf = [0u8; 1024];
18303 rng.fill_bytes(&mut buf);
18304 let mut unstructured = Unstructured::new(&buf);
18305 Self::arbitrary(&mut unstructured).unwrap_or_default()
18306 }
18307}
18308impl Default for HIL_STATE_QUATERNION_DATA {
18309 fn default() -> Self {
18310 Self::DEFAULT.clone()
18311 }
18312}
18313impl MessageData for HIL_STATE_QUATERNION_DATA {
18314 type Message = MavMessage;
18315 const ID: u32 = 115u32;
18316 const NAME: &'static str = "HIL_STATE_QUATERNION";
18317 const EXTRA_CRC: u8 = 4u8;
18318 const ENCODED_LEN: usize = 64usize;
18319 fn deser(
18320 _version: MavlinkVersion,
18321 __input: &[u8],
18322 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18323 let avail_len = __input.len();
18324 let mut payload_buf = [0; Self::ENCODED_LEN];
18325 let mut buf = if avail_len < Self::ENCODED_LEN {
18326 payload_buf[0..avail_len].copy_from_slice(__input);
18327 Bytes::new(&payload_buf)
18328 } else {
18329 Bytes::new(__input)
18330 };
18331 let mut __struct = Self::default();
18332 __struct.time_usec = buf.get_u64_le()?;
18333 for v in &mut __struct.attitude_quaternion {
18334 let val = buf.get_f32_le()?;
18335 *v = val;
18336 }
18337 __struct.rollspeed = buf.get_f32_le()?;
18338 __struct.pitchspeed = buf.get_f32_le()?;
18339 __struct.yawspeed = buf.get_f32_le()?;
18340 __struct.lat = buf.get_i32_le()?;
18341 __struct.lon = buf.get_i32_le()?;
18342 __struct.alt = buf.get_i32_le()?;
18343 __struct.vx = buf.get_i16_le()?;
18344 __struct.vy = buf.get_i16_le()?;
18345 __struct.vz = buf.get_i16_le()?;
18346 __struct.ind_airspeed = buf.get_u16_le()?;
18347 __struct.true_airspeed = buf.get_u16_le()?;
18348 __struct.xacc = buf.get_i16_le()?;
18349 __struct.yacc = buf.get_i16_le()?;
18350 __struct.zacc = buf.get_i16_le()?;
18351 Ok(__struct)
18352 }
18353 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18354 let mut __tmp = BytesMut::new(bytes);
18355 #[allow(clippy::absurd_extreme_comparisons)]
18356 #[allow(unused_comparisons)]
18357 if __tmp.remaining() < Self::ENCODED_LEN {
18358 panic!(
18359 "buffer is too small (need {} bytes, but got {})",
18360 Self::ENCODED_LEN,
18361 __tmp.remaining(),
18362 )
18363 }
18364 __tmp.put_u64_le(self.time_usec);
18365 for val in &self.attitude_quaternion {
18366 __tmp.put_f32_le(*val);
18367 }
18368 __tmp.put_f32_le(self.rollspeed);
18369 __tmp.put_f32_le(self.pitchspeed);
18370 __tmp.put_f32_le(self.yawspeed);
18371 __tmp.put_i32_le(self.lat);
18372 __tmp.put_i32_le(self.lon);
18373 __tmp.put_i32_le(self.alt);
18374 __tmp.put_i16_le(self.vx);
18375 __tmp.put_i16_le(self.vy);
18376 __tmp.put_i16_le(self.vz);
18377 __tmp.put_u16_le(self.ind_airspeed);
18378 __tmp.put_u16_le(self.true_airspeed);
18379 __tmp.put_i16_le(self.xacc);
18380 __tmp.put_i16_le(self.yacc);
18381 __tmp.put_i16_le(self.zacc);
18382 if matches!(version, MavlinkVersion::V2) {
18383 let len = __tmp.len();
18384 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18385 } else {
18386 __tmp.len()
18387 }
18388 }
18389}
18390#[doc = "Contains the home position. \tThe home position is the default position that the system will return to and land on. \tThe position must be set automatically by the system during the takeoff, and may also be explicitly set using MAV_CMD_DO_SET_HOME. \tThe global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. \tUnder normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. \tThe approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. Note: this message can be requested by sending the MAV_CMD_REQUEST_MESSAGE with param1=242 (or the deprecated MAV_CMD_GET_HOME_POSITION command)."]
18391#[doc = ""]
18392#[doc = "ID: 242"]
18393#[derive(Debug, Clone, PartialEq)]
18394#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18395#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18396#[cfg_attr(feature = "ts", derive(TS))]
18397#[cfg_attr(feature = "ts", ts(export))]
18398pub struct HOME_POSITION_DATA {
18399 #[doc = "Latitude (WGS84)"]
18400 pub latitude: i32,
18401 #[doc = "Longitude (WGS84)"]
18402 pub longitude: i32,
18403 #[doc = "Altitude (MSL). Positive for up."]
18404 pub altitude: i32,
18405 #[doc = "Local X position of this position in the local coordinate frame (NED)"]
18406 pub x: f32,
18407 #[doc = "Local Y position of this position in the local coordinate frame (NED)"]
18408 pub y: f32,
18409 #[doc = "Local Z position of this position in the local coordinate frame (NED: positive \"down\")"]
18410 pub z: f32,
18411 #[doc = "Quaternion indicating world-to-surface-normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground. All fields should be set to NaN if an accurate quaternion for both heading and surface slope cannot be supplied."]
18412 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18413 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
18414 pub q: [f32; 4],
18415 #[doc = "Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
18416 pub approach_x: f32,
18417 #[doc = "Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
18418 pub approach_y: f32,
18419 #[doc = "Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
18420 pub approach_z: f32,
18421 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
18422 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18423 pub time_usec: u64,
18424}
18425impl HOME_POSITION_DATA {
18426 pub const ENCODED_LEN: usize = 60usize;
18427 pub const DEFAULT: Self = Self {
18428 latitude: 0_i32,
18429 longitude: 0_i32,
18430 altitude: 0_i32,
18431 x: 0.0_f32,
18432 y: 0.0_f32,
18433 z: 0.0_f32,
18434 q: [0.0_f32; 4usize],
18435 approach_x: 0.0_f32,
18436 approach_y: 0.0_f32,
18437 approach_z: 0.0_f32,
18438 time_usec: 0_u64,
18439 };
18440 #[cfg(feature = "arbitrary")]
18441 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18442 use arbitrary::{Arbitrary, Unstructured};
18443 let mut buf = [0u8; 1024];
18444 rng.fill_bytes(&mut buf);
18445 let mut unstructured = Unstructured::new(&buf);
18446 Self::arbitrary(&mut unstructured).unwrap_or_default()
18447 }
18448}
18449impl Default for HOME_POSITION_DATA {
18450 fn default() -> Self {
18451 Self::DEFAULT.clone()
18452 }
18453}
18454impl MessageData for HOME_POSITION_DATA {
18455 type Message = MavMessage;
18456 const ID: u32 = 242u32;
18457 const NAME: &'static str = "HOME_POSITION";
18458 const EXTRA_CRC: u8 = 104u8;
18459 const ENCODED_LEN: usize = 60usize;
18460 fn deser(
18461 _version: MavlinkVersion,
18462 __input: &[u8],
18463 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18464 let avail_len = __input.len();
18465 let mut payload_buf = [0; Self::ENCODED_LEN];
18466 let mut buf = if avail_len < Self::ENCODED_LEN {
18467 payload_buf[0..avail_len].copy_from_slice(__input);
18468 Bytes::new(&payload_buf)
18469 } else {
18470 Bytes::new(__input)
18471 };
18472 let mut __struct = Self::default();
18473 __struct.latitude = buf.get_i32_le()?;
18474 __struct.longitude = buf.get_i32_le()?;
18475 __struct.altitude = buf.get_i32_le()?;
18476 __struct.x = buf.get_f32_le()?;
18477 __struct.y = buf.get_f32_le()?;
18478 __struct.z = buf.get_f32_le()?;
18479 for v in &mut __struct.q {
18480 let val = buf.get_f32_le()?;
18481 *v = val;
18482 }
18483 __struct.approach_x = buf.get_f32_le()?;
18484 __struct.approach_y = buf.get_f32_le()?;
18485 __struct.approach_z = buf.get_f32_le()?;
18486 __struct.time_usec = buf.get_u64_le()?;
18487 Ok(__struct)
18488 }
18489 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18490 let mut __tmp = BytesMut::new(bytes);
18491 #[allow(clippy::absurd_extreme_comparisons)]
18492 #[allow(unused_comparisons)]
18493 if __tmp.remaining() < Self::ENCODED_LEN {
18494 panic!(
18495 "buffer is too small (need {} bytes, but got {})",
18496 Self::ENCODED_LEN,
18497 __tmp.remaining(),
18498 )
18499 }
18500 __tmp.put_i32_le(self.latitude);
18501 __tmp.put_i32_le(self.longitude);
18502 __tmp.put_i32_le(self.altitude);
18503 __tmp.put_f32_le(self.x);
18504 __tmp.put_f32_le(self.y);
18505 __tmp.put_f32_le(self.z);
18506 for val in &self.q {
18507 __tmp.put_f32_le(*val);
18508 }
18509 __tmp.put_f32_le(self.approach_x);
18510 __tmp.put_f32_le(self.approach_y);
18511 __tmp.put_f32_le(self.approach_z);
18512 if matches!(version, MavlinkVersion::V2) {
18513 __tmp.put_u64_le(self.time_usec);
18514 let len = __tmp.len();
18515 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18516 } else {
18517 __tmp.len()
18518 }
18519 }
18520}
18521#[doc = "Temperature and humidity from hygrometer."]
18522#[doc = ""]
18523#[doc = "ID: 12920"]
18524#[derive(Debug, Clone, PartialEq)]
18525#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18526#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18527#[cfg_attr(feature = "ts", derive(TS))]
18528#[cfg_attr(feature = "ts", ts(export))]
18529pub struct HYGROMETER_SENSOR_DATA {
18530 #[doc = "Temperature"]
18531 pub temperature: i16,
18532 #[doc = "Humidity"]
18533 pub humidity: u16,
18534 #[doc = "Hygrometer ID"]
18535 pub id: u8,
18536}
18537impl HYGROMETER_SENSOR_DATA {
18538 pub const ENCODED_LEN: usize = 5usize;
18539 pub const DEFAULT: Self = Self {
18540 temperature: 0_i16,
18541 humidity: 0_u16,
18542 id: 0_u8,
18543 };
18544 #[cfg(feature = "arbitrary")]
18545 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18546 use arbitrary::{Arbitrary, Unstructured};
18547 let mut buf = [0u8; 1024];
18548 rng.fill_bytes(&mut buf);
18549 let mut unstructured = Unstructured::new(&buf);
18550 Self::arbitrary(&mut unstructured).unwrap_or_default()
18551 }
18552}
18553impl Default for HYGROMETER_SENSOR_DATA {
18554 fn default() -> Self {
18555 Self::DEFAULT.clone()
18556 }
18557}
18558impl MessageData for HYGROMETER_SENSOR_DATA {
18559 type Message = MavMessage;
18560 const ID: u32 = 12920u32;
18561 const NAME: &'static str = "HYGROMETER_SENSOR";
18562 const EXTRA_CRC: u8 = 20u8;
18563 const ENCODED_LEN: usize = 5usize;
18564 fn deser(
18565 _version: MavlinkVersion,
18566 __input: &[u8],
18567 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18568 let avail_len = __input.len();
18569 let mut payload_buf = [0; Self::ENCODED_LEN];
18570 let mut buf = if avail_len < Self::ENCODED_LEN {
18571 payload_buf[0..avail_len].copy_from_slice(__input);
18572 Bytes::new(&payload_buf)
18573 } else {
18574 Bytes::new(__input)
18575 };
18576 let mut __struct = Self::default();
18577 __struct.temperature = buf.get_i16_le()?;
18578 __struct.humidity = buf.get_u16_le()?;
18579 __struct.id = buf.get_u8()?;
18580 Ok(__struct)
18581 }
18582 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18583 let mut __tmp = BytesMut::new(bytes);
18584 #[allow(clippy::absurd_extreme_comparisons)]
18585 #[allow(unused_comparisons)]
18586 if __tmp.remaining() < Self::ENCODED_LEN {
18587 panic!(
18588 "buffer is too small (need {} bytes, but got {})",
18589 Self::ENCODED_LEN,
18590 __tmp.remaining(),
18591 )
18592 }
18593 __tmp.put_i16_le(self.temperature);
18594 __tmp.put_u16_le(self.humidity);
18595 __tmp.put_u8(self.id);
18596 if matches!(version, MavlinkVersion::V2) {
18597 let len = __tmp.len();
18598 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18599 } else {
18600 __tmp.len()
18601 }
18602 }
18603}
18604#[doc = "Illuminator status."]
18605#[doc = ""]
18606#[doc = "ID: 440"]
18607#[derive(Debug, Clone, PartialEq)]
18608#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18609#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18610#[cfg_attr(feature = "ts", derive(TS))]
18611#[cfg_attr(feature = "ts", ts(export))]
18612pub struct ILLUMINATOR_STATUS_DATA {
18613 #[doc = "Time since the start-up of the illuminator in ms"]
18614 pub uptime_ms: u32,
18615 #[doc = "Errors"]
18616 pub error_status: IlluminatorErrorFlags,
18617 #[doc = "Illuminator brightness"]
18618 pub brightness: f32,
18619 #[doc = "Illuminator strobing period in seconds"]
18620 pub strobe_period: f32,
18621 #[doc = "Illuminator strobing duty cycle"]
18622 pub strobe_duty_cycle: f32,
18623 #[doc = "Temperature in Celsius"]
18624 pub temp_c: f32,
18625 #[doc = "Minimum strobing period in seconds"]
18626 pub min_strobe_period: f32,
18627 #[doc = "Maximum strobing period in seconds"]
18628 pub max_strobe_period: f32,
18629 #[doc = "0: Illuminators OFF, 1: Illuminators ON"]
18630 pub enable: u8,
18631 #[doc = "Supported illuminator modes"]
18632 pub mode_bitmask: IlluminatorMode,
18633 #[doc = "Illuminator mode"]
18634 pub mode: IlluminatorMode,
18635}
18636impl ILLUMINATOR_STATUS_DATA {
18637 pub const ENCODED_LEN: usize = 35usize;
18638 pub const DEFAULT: Self = Self {
18639 uptime_ms: 0_u32,
18640 error_status: IlluminatorErrorFlags::DEFAULT,
18641 brightness: 0.0_f32,
18642 strobe_period: 0.0_f32,
18643 strobe_duty_cycle: 0.0_f32,
18644 temp_c: 0.0_f32,
18645 min_strobe_period: 0.0_f32,
18646 max_strobe_period: 0.0_f32,
18647 enable: 0_u8,
18648 mode_bitmask: IlluminatorMode::DEFAULT,
18649 mode: IlluminatorMode::DEFAULT,
18650 };
18651 #[cfg(feature = "arbitrary")]
18652 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18653 use arbitrary::{Arbitrary, Unstructured};
18654 let mut buf = [0u8; 1024];
18655 rng.fill_bytes(&mut buf);
18656 let mut unstructured = Unstructured::new(&buf);
18657 Self::arbitrary(&mut unstructured).unwrap_or_default()
18658 }
18659}
18660impl Default for ILLUMINATOR_STATUS_DATA {
18661 fn default() -> Self {
18662 Self::DEFAULT.clone()
18663 }
18664}
18665impl MessageData for ILLUMINATOR_STATUS_DATA {
18666 type Message = MavMessage;
18667 const ID: u32 = 440u32;
18668 const NAME: &'static str = "ILLUMINATOR_STATUS";
18669 const EXTRA_CRC: u8 = 66u8;
18670 const ENCODED_LEN: usize = 35usize;
18671 fn deser(
18672 _version: MavlinkVersion,
18673 __input: &[u8],
18674 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18675 let avail_len = __input.len();
18676 let mut payload_buf = [0; Self::ENCODED_LEN];
18677 let mut buf = if avail_len < Self::ENCODED_LEN {
18678 payload_buf[0..avail_len].copy_from_slice(__input);
18679 Bytes::new(&payload_buf)
18680 } else {
18681 Bytes::new(__input)
18682 };
18683 let mut __struct = Self::default();
18684 __struct.uptime_ms = buf.get_u32_le()?;
18685 let tmp = buf.get_u32_le()?;
18686 __struct.error_status = IlluminatorErrorFlags::from_bits(
18687 tmp as <IlluminatorErrorFlags as Flags>::Bits,
18688 )
18689 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
18690 flag_type: "IlluminatorErrorFlags",
18691 value: tmp as u64,
18692 })?;
18693 __struct.brightness = buf.get_f32_le()?;
18694 __struct.strobe_period = buf.get_f32_le()?;
18695 __struct.strobe_duty_cycle = buf.get_f32_le()?;
18696 __struct.temp_c = buf.get_f32_le()?;
18697 __struct.min_strobe_period = buf.get_f32_le()?;
18698 __struct.max_strobe_period = buf.get_f32_le()?;
18699 __struct.enable = buf.get_u8()?;
18700 let tmp = buf.get_u8()?;
18701 __struct.mode_bitmask =
18702 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18703 enum_type: "IlluminatorMode",
18704 value: tmp as u64,
18705 })?;
18706 let tmp = buf.get_u8()?;
18707 __struct.mode =
18708 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18709 enum_type: "IlluminatorMode",
18710 value: tmp as u64,
18711 })?;
18712 Ok(__struct)
18713 }
18714 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18715 let mut __tmp = BytesMut::new(bytes);
18716 #[allow(clippy::absurd_extreme_comparisons)]
18717 #[allow(unused_comparisons)]
18718 if __tmp.remaining() < Self::ENCODED_LEN {
18719 panic!(
18720 "buffer is too small (need {} bytes, but got {})",
18721 Self::ENCODED_LEN,
18722 __tmp.remaining(),
18723 )
18724 }
18725 __tmp.put_u32_le(self.uptime_ms);
18726 __tmp.put_u32_le(self.error_status.bits() as u32);
18727 __tmp.put_f32_le(self.brightness);
18728 __tmp.put_f32_le(self.strobe_period);
18729 __tmp.put_f32_le(self.strobe_duty_cycle);
18730 __tmp.put_f32_le(self.temp_c);
18731 __tmp.put_f32_le(self.min_strobe_period);
18732 __tmp.put_f32_le(self.max_strobe_period);
18733 __tmp.put_u8(self.enable);
18734 __tmp.put_u8(self.mode_bitmask as u8);
18735 __tmp.put_u8(self.mode as u8);
18736 if matches!(version, MavlinkVersion::V2) {
18737 let len = __tmp.len();
18738 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18739 } else {
18740 __tmp.len()
18741 }
18742 }
18743}
18744#[doc = "Status of the Iridium SBD link."]
18745#[doc = ""]
18746#[doc = "ID: 335"]
18747#[derive(Debug, Clone, PartialEq)]
18748#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18749#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18750#[cfg_attr(feature = "ts", derive(TS))]
18751#[cfg_attr(feature = "ts", ts(export))]
18752pub struct ISBD_LINK_STATUS_DATA {
18753 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
18754 pub timestamp: u64,
18755 #[doc = "Timestamp of the last successful sbd session. The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
18756 pub last_heartbeat: u64,
18757 #[doc = "Number of failed SBD sessions."]
18758 pub failed_sessions: u16,
18759 #[doc = "Number of successful SBD sessions."]
18760 pub successful_sessions: u16,
18761 #[doc = "Signal quality equal to the number of bars displayed on the ISU signal strength indicator. Range is 0 to 5, where 0 indicates no signal and 5 indicates maximum signal strength."]
18762 pub signal_quality: u8,
18763 #[doc = "1: Ring call pending, 0: No call pending."]
18764 pub ring_pending: u8,
18765 #[doc = "1: Transmission session pending, 0: No transmission session pending."]
18766 pub tx_session_pending: u8,
18767 #[doc = "1: Receiving session pending, 0: No receiving session pending."]
18768 pub rx_session_pending: u8,
18769}
18770impl ISBD_LINK_STATUS_DATA {
18771 pub const ENCODED_LEN: usize = 24usize;
18772 pub const DEFAULT: Self = Self {
18773 timestamp: 0_u64,
18774 last_heartbeat: 0_u64,
18775 failed_sessions: 0_u16,
18776 successful_sessions: 0_u16,
18777 signal_quality: 0_u8,
18778 ring_pending: 0_u8,
18779 tx_session_pending: 0_u8,
18780 rx_session_pending: 0_u8,
18781 };
18782 #[cfg(feature = "arbitrary")]
18783 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18784 use arbitrary::{Arbitrary, Unstructured};
18785 let mut buf = [0u8; 1024];
18786 rng.fill_bytes(&mut buf);
18787 let mut unstructured = Unstructured::new(&buf);
18788 Self::arbitrary(&mut unstructured).unwrap_or_default()
18789 }
18790}
18791impl Default for ISBD_LINK_STATUS_DATA {
18792 fn default() -> Self {
18793 Self::DEFAULT.clone()
18794 }
18795}
18796impl MessageData for ISBD_LINK_STATUS_DATA {
18797 type Message = MavMessage;
18798 const ID: u32 = 335u32;
18799 const NAME: &'static str = "ISBD_LINK_STATUS";
18800 const EXTRA_CRC: u8 = 225u8;
18801 const ENCODED_LEN: usize = 24usize;
18802 fn deser(
18803 _version: MavlinkVersion,
18804 __input: &[u8],
18805 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18806 let avail_len = __input.len();
18807 let mut payload_buf = [0; Self::ENCODED_LEN];
18808 let mut buf = if avail_len < Self::ENCODED_LEN {
18809 payload_buf[0..avail_len].copy_from_slice(__input);
18810 Bytes::new(&payload_buf)
18811 } else {
18812 Bytes::new(__input)
18813 };
18814 let mut __struct = Self::default();
18815 __struct.timestamp = buf.get_u64_le()?;
18816 __struct.last_heartbeat = buf.get_u64_le()?;
18817 __struct.failed_sessions = buf.get_u16_le()?;
18818 __struct.successful_sessions = buf.get_u16_le()?;
18819 __struct.signal_quality = buf.get_u8()?;
18820 __struct.ring_pending = buf.get_u8()?;
18821 __struct.tx_session_pending = buf.get_u8()?;
18822 __struct.rx_session_pending = buf.get_u8()?;
18823 Ok(__struct)
18824 }
18825 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18826 let mut __tmp = BytesMut::new(bytes);
18827 #[allow(clippy::absurd_extreme_comparisons)]
18828 #[allow(unused_comparisons)]
18829 if __tmp.remaining() < Self::ENCODED_LEN {
18830 panic!(
18831 "buffer is too small (need {} bytes, but got {})",
18832 Self::ENCODED_LEN,
18833 __tmp.remaining(),
18834 )
18835 }
18836 __tmp.put_u64_le(self.timestamp);
18837 __tmp.put_u64_le(self.last_heartbeat);
18838 __tmp.put_u16_le(self.failed_sessions);
18839 __tmp.put_u16_le(self.successful_sessions);
18840 __tmp.put_u8(self.signal_quality);
18841 __tmp.put_u8(self.ring_pending);
18842 __tmp.put_u8(self.tx_session_pending);
18843 __tmp.put_u8(self.rx_session_pending);
18844 if matches!(version, MavlinkVersion::V2) {
18845 let len = __tmp.len();
18846 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18847 } else {
18848 __tmp.len()
18849 }
18850 }
18851}
18852#[doc = "The location of a landing target. See: <https://mavlink.io/en/services/landing_target.html>."]
18853#[doc = ""]
18854#[doc = "ID: 149"]
18855#[derive(Debug, Clone, PartialEq)]
18856#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18857#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18858#[cfg_attr(feature = "ts", derive(TS))]
18859#[cfg_attr(feature = "ts", ts(export))]
18860pub struct LANDING_TARGET_DATA {
18861 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
18862 pub time_usec: u64,
18863 #[doc = "X-axis angular offset of the target from the center of the image"]
18864 pub angle_x: f32,
18865 #[doc = "Y-axis angular offset of the target from the center of the image"]
18866 pub angle_y: f32,
18867 #[doc = "Distance to the target from the vehicle"]
18868 pub distance: f32,
18869 #[doc = "Size of target along x-axis"]
18870 pub size_x: f32,
18871 #[doc = "Size of target along y-axis"]
18872 pub size_y: f32,
18873 #[doc = "The ID of the target if multiple targets are present"]
18874 pub target_num: u8,
18875 #[doc = "Coordinate frame used for following fields."]
18876 pub frame: MavFrame,
18877 #[doc = "X Position of the landing target in MAV_FRAME"]
18878 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18879 pub x: f32,
18880 #[doc = "Y Position of the landing target in MAV_FRAME"]
18881 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18882 pub y: f32,
18883 #[doc = "Z Position of the landing target in MAV_FRAME"]
18884 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18885 pub z: f32,
18886 #[doc = "Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
18887 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18888 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18889 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
18890 pub q: [f32; 4],
18891 #[doc = "Type of landing target"]
18892 #[cfg_attr(feature = "serde", serde(default))]
18893 pub mavtype: LandingTargetType,
18894 #[doc = "Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid)."]
18895 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18896 pub position_valid: u8,
18897}
18898impl LANDING_TARGET_DATA {
18899 pub const ENCODED_LEN: usize = 60usize;
18900 pub const DEFAULT: Self = Self {
18901 time_usec: 0_u64,
18902 angle_x: 0.0_f32,
18903 angle_y: 0.0_f32,
18904 distance: 0.0_f32,
18905 size_x: 0.0_f32,
18906 size_y: 0.0_f32,
18907 target_num: 0_u8,
18908 frame: MavFrame::DEFAULT,
18909 x: 0.0_f32,
18910 y: 0.0_f32,
18911 z: 0.0_f32,
18912 q: [0.0_f32; 4usize],
18913 mavtype: LandingTargetType::DEFAULT,
18914 position_valid: 0_u8,
18915 };
18916 #[cfg(feature = "arbitrary")]
18917 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18918 use arbitrary::{Arbitrary, Unstructured};
18919 let mut buf = [0u8; 1024];
18920 rng.fill_bytes(&mut buf);
18921 let mut unstructured = Unstructured::new(&buf);
18922 Self::arbitrary(&mut unstructured).unwrap_or_default()
18923 }
18924}
18925impl Default for LANDING_TARGET_DATA {
18926 fn default() -> Self {
18927 Self::DEFAULT.clone()
18928 }
18929}
18930impl MessageData for LANDING_TARGET_DATA {
18931 type Message = MavMessage;
18932 const ID: u32 = 149u32;
18933 const NAME: &'static str = "LANDING_TARGET";
18934 const EXTRA_CRC: u8 = 200u8;
18935 const ENCODED_LEN: usize = 60usize;
18936 fn deser(
18937 _version: MavlinkVersion,
18938 __input: &[u8],
18939 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18940 let avail_len = __input.len();
18941 let mut payload_buf = [0; Self::ENCODED_LEN];
18942 let mut buf = if avail_len < Self::ENCODED_LEN {
18943 payload_buf[0..avail_len].copy_from_slice(__input);
18944 Bytes::new(&payload_buf)
18945 } else {
18946 Bytes::new(__input)
18947 };
18948 let mut __struct = Self::default();
18949 __struct.time_usec = buf.get_u64_le()?;
18950 __struct.angle_x = buf.get_f32_le()?;
18951 __struct.angle_y = buf.get_f32_le()?;
18952 __struct.distance = buf.get_f32_le()?;
18953 __struct.size_x = buf.get_f32_le()?;
18954 __struct.size_y = buf.get_f32_le()?;
18955 __struct.target_num = buf.get_u8()?;
18956 let tmp = buf.get_u8()?;
18957 __struct.frame =
18958 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18959 enum_type: "MavFrame",
18960 value: tmp as u64,
18961 })?;
18962 __struct.x = buf.get_f32_le()?;
18963 __struct.y = buf.get_f32_le()?;
18964 __struct.z = buf.get_f32_le()?;
18965 for v in &mut __struct.q {
18966 let val = buf.get_f32_le()?;
18967 *v = val;
18968 }
18969 let tmp = buf.get_u8()?;
18970 __struct.mavtype =
18971 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18972 enum_type: "LandingTargetType",
18973 value: tmp as u64,
18974 })?;
18975 __struct.position_valid = buf.get_u8()?;
18976 Ok(__struct)
18977 }
18978 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18979 let mut __tmp = BytesMut::new(bytes);
18980 #[allow(clippy::absurd_extreme_comparisons)]
18981 #[allow(unused_comparisons)]
18982 if __tmp.remaining() < Self::ENCODED_LEN {
18983 panic!(
18984 "buffer is too small (need {} bytes, but got {})",
18985 Self::ENCODED_LEN,
18986 __tmp.remaining(),
18987 )
18988 }
18989 __tmp.put_u64_le(self.time_usec);
18990 __tmp.put_f32_le(self.angle_x);
18991 __tmp.put_f32_le(self.angle_y);
18992 __tmp.put_f32_le(self.distance);
18993 __tmp.put_f32_le(self.size_x);
18994 __tmp.put_f32_le(self.size_y);
18995 __tmp.put_u8(self.target_num);
18996 __tmp.put_u8(self.frame as u8);
18997 if matches!(version, MavlinkVersion::V2) {
18998 __tmp.put_f32_le(self.x);
18999 __tmp.put_f32_le(self.y);
19000 __tmp.put_f32_le(self.z);
19001 for val in &self.q {
19002 __tmp.put_f32_le(*val);
19003 }
19004 __tmp.put_u8(self.mavtype as u8);
19005 __tmp.put_u8(self.position_valid);
19006 let len = __tmp.len();
19007 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19008 } else {
19009 __tmp.len()
19010 }
19011 }
19012}
19013#[doc = "Status generated in each node in the communication chain and injected into MAVLink stream."]
19014#[doc = ""]
19015#[doc = "ID: 8"]
19016#[derive(Debug, Clone, PartialEq)]
19017#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19018#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19019#[cfg_attr(feature = "ts", derive(TS))]
19020#[cfg_attr(feature = "ts", ts(export))]
19021pub struct LINK_NODE_STATUS_DATA {
19022 #[doc = "Timestamp (time since system boot)."]
19023 pub timestamp: u64,
19024 #[doc = "Transmit rate"]
19025 pub tx_rate: u32,
19026 #[doc = "Receive rate"]
19027 pub rx_rate: u32,
19028 #[doc = "Messages sent"]
19029 pub messages_sent: u32,
19030 #[doc = "Messages received (estimated from counting seq)"]
19031 pub messages_received: u32,
19032 #[doc = "Messages lost (estimated from counting seq)"]
19033 pub messages_lost: u32,
19034 #[doc = "Number of bytes that could not be parsed correctly."]
19035 pub rx_parse_err: u16,
19036 #[doc = "Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX"]
19037 pub tx_overflows: u16,
19038 #[doc = "Receive buffer overflows. This number wraps around as it reaches UINT16_MAX"]
19039 pub rx_overflows: u16,
19040 #[doc = "Remaining free transmit buffer space"]
19041 pub tx_buf: u8,
19042 #[doc = "Remaining free receive buffer space"]
19043 pub rx_buf: u8,
19044}
19045impl LINK_NODE_STATUS_DATA {
19046 pub const ENCODED_LEN: usize = 36usize;
19047 pub const DEFAULT: Self = Self {
19048 timestamp: 0_u64,
19049 tx_rate: 0_u32,
19050 rx_rate: 0_u32,
19051 messages_sent: 0_u32,
19052 messages_received: 0_u32,
19053 messages_lost: 0_u32,
19054 rx_parse_err: 0_u16,
19055 tx_overflows: 0_u16,
19056 rx_overflows: 0_u16,
19057 tx_buf: 0_u8,
19058 rx_buf: 0_u8,
19059 };
19060 #[cfg(feature = "arbitrary")]
19061 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19062 use arbitrary::{Arbitrary, Unstructured};
19063 let mut buf = [0u8; 1024];
19064 rng.fill_bytes(&mut buf);
19065 let mut unstructured = Unstructured::new(&buf);
19066 Self::arbitrary(&mut unstructured).unwrap_or_default()
19067 }
19068}
19069impl Default for LINK_NODE_STATUS_DATA {
19070 fn default() -> Self {
19071 Self::DEFAULT.clone()
19072 }
19073}
19074impl MessageData for LINK_NODE_STATUS_DATA {
19075 type Message = MavMessage;
19076 const ID: u32 = 8u32;
19077 const NAME: &'static str = "LINK_NODE_STATUS";
19078 const EXTRA_CRC: u8 = 117u8;
19079 const ENCODED_LEN: usize = 36usize;
19080 fn deser(
19081 _version: MavlinkVersion,
19082 __input: &[u8],
19083 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19084 let avail_len = __input.len();
19085 let mut payload_buf = [0; Self::ENCODED_LEN];
19086 let mut buf = if avail_len < Self::ENCODED_LEN {
19087 payload_buf[0..avail_len].copy_from_slice(__input);
19088 Bytes::new(&payload_buf)
19089 } else {
19090 Bytes::new(__input)
19091 };
19092 let mut __struct = Self::default();
19093 __struct.timestamp = buf.get_u64_le()?;
19094 __struct.tx_rate = buf.get_u32_le()?;
19095 __struct.rx_rate = buf.get_u32_le()?;
19096 __struct.messages_sent = buf.get_u32_le()?;
19097 __struct.messages_received = buf.get_u32_le()?;
19098 __struct.messages_lost = buf.get_u32_le()?;
19099 __struct.rx_parse_err = buf.get_u16_le()?;
19100 __struct.tx_overflows = buf.get_u16_le()?;
19101 __struct.rx_overflows = buf.get_u16_le()?;
19102 __struct.tx_buf = buf.get_u8()?;
19103 __struct.rx_buf = buf.get_u8()?;
19104 Ok(__struct)
19105 }
19106 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19107 let mut __tmp = BytesMut::new(bytes);
19108 #[allow(clippy::absurd_extreme_comparisons)]
19109 #[allow(unused_comparisons)]
19110 if __tmp.remaining() < Self::ENCODED_LEN {
19111 panic!(
19112 "buffer is too small (need {} bytes, but got {})",
19113 Self::ENCODED_LEN,
19114 __tmp.remaining(),
19115 )
19116 }
19117 __tmp.put_u64_le(self.timestamp);
19118 __tmp.put_u32_le(self.tx_rate);
19119 __tmp.put_u32_le(self.rx_rate);
19120 __tmp.put_u32_le(self.messages_sent);
19121 __tmp.put_u32_le(self.messages_received);
19122 __tmp.put_u32_le(self.messages_lost);
19123 __tmp.put_u16_le(self.rx_parse_err);
19124 __tmp.put_u16_le(self.tx_overflows);
19125 __tmp.put_u16_le(self.rx_overflows);
19126 __tmp.put_u8(self.tx_buf);
19127 __tmp.put_u8(self.rx_buf);
19128 if matches!(version, MavlinkVersion::V2) {
19129 let len = __tmp.len();
19130 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19131 } else {
19132 __tmp.len()
19133 }
19134 }
19135}
19136#[doc = "The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)."]
19137#[doc = ""]
19138#[doc = "ID: 32"]
19139#[derive(Debug, Clone, PartialEq)]
19140#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19141#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19142#[cfg_attr(feature = "ts", derive(TS))]
19143#[cfg_attr(feature = "ts", ts(export))]
19144pub struct LOCAL_POSITION_NED_DATA {
19145 #[doc = "Timestamp (time since system boot)."]
19146 pub time_boot_ms: u32,
19147 #[doc = "X Position"]
19148 pub x: f32,
19149 #[doc = "Y Position"]
19150 pub y: f32,
19151 #[doc = "Z Position"]
19152 pub z: f32,
19153 #[doc = "X Speed"]
19154 pub vx: f32,
19155 #[doc = "Y Speed"]
19156 pub vy: f32,
19157 #[doc = "Z Speed"]
19158 pub vz: f32,
19159}
19160impl LOCAL_POSITION_NED_DATA {
19161 pub const ENCODED_LEN: usize = 28usize;
19162 pub const DEFAULT: Self = Self {
19163 time_boot_ms: 0_u32,
19164 x: 0.0_f32,
19165 y: 0.0_f32,
19166 z: 0.0_f32,
19167 vx: 0.0_f32,
19168 vy: 0.0_f32,
19169 vz: 0.0_f32,
19170 };
19171 #[cfg(feature = "arbitrary")]
19172 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19173 use arbitrary::{Arbitrary, Unstructured};
19174 let mut buf = [0u8; 1024];
19175 rng.fill_bytes(&mut buf);
19176 let mut unstructured = Unstructured::new(&buf);
19177 Self::arbitrary(&mut unstructured).unwrap_or_default()
19178 }
19179}
19180impl Default for LOCAL_POSITION_NED_DATA {
19181 fn default() -> Self {
19182 Self::DEFAULT.clone()
19183 }
19184}
19185impl MessageData for LOCAL_POSITION_NED_DATA {
19186 type Message = MavMessage;
19187 const ID: u32 = 32u32;
19188 const NAME: &'static str = "LOCAL_POSITION_NED";
19189 const EXTRA_CRC: u8 = 185u8;
19190 const ENCODED_LEN: usize = 28usize;
19191 fn deser(
19192 _version: MavlinkVersion,
19193 __input: &[u8],
19194 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19195 let avail_len = __input.len();
19196 let mut payload_buf = [0; Self::ENCODED_LEN];
19197 let mut buf = if avail_len < Self::ENCODED_LEN {
19198 payload_buf[0..avail_len].copy_from_slice(__input);
19199 Bytes::new(&payload_buf)
19200 } else {
19201 Bytes::new(__input)
19202 };
19203 let mut __struct = Self::default();
19204 __struct.time_boot_ms = buf.get_u32_le()?;
19205 __struct.x = buf.get_f32_le()?;
19206 __struct.y = buf.get_f32_le()?;
19207 __struct.z = buf.get_f32_le()?;
19208 __struct.vx = buf.get_f32_le()?;
19209 __struct.vy = buf.get_f32_le()?;
19210 __struct.vz = buf.get_f32_le()?;
19211 Ok(__struct)
19212 }
19213 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19214 let mut __tmp = BytesMut::new(bytes);
19215 #[allow(clippy::absurd_extreme_comparisons)]
19216 #[allow(unused_comparisons)]
19217 if __tmp.remaining() < Self::ENCODED_LEN {
19218 panic!(
19219 "buffer is too small (need {} bytes, but got {})",
19220 Self::ENCODED_LEN,
19221 __tmp.remaining(),
19222 )
19223 }
19224 __tmp.put_u32_le(self.time_boot_ms);
19225 __tmp.put_f32_le(self.x);
19226 __tmp.put_f32_le(self.y);
19227 __tmp.put_f32_le(self.z);
19228 __tmp.put_f32_le(self.vx);
19229 __tmp.put_f32_le(self.vy);
19230 __tmp.put_f32_le(self.vz);
19231 if matches!(version, MavlinkVersion::V2) {
19232 let len = __tmp.len();
19233 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19234 } else {
19235 __tmp.len()
19236 }
19237 }
19238}
19239#[doc = "The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)."]
19240#[doc = ""]
19241#[doc = "ID: 64"]
19242#[derive(Debug, Clone, PartialEq)]
19243#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19244#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19245#[cfg_attr(feature = "ts", derive(TS))]
19246#[cfg_attr(feature = "ts", ts(export))]
19247pub struct LOCAL_POSITION_NED_COV_DATA {
19248 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
19249 pub time_usec: u64,
19250 #[doc = "X Position"]
19251 pub x: f32,
19252 #[doc = "Y Position"]
19253 pub y: f32,
19254 #[doc = "Z Position"]
19255 pub z: f32,
19256 #[doc = "X Speed"]
19257 pub vx: f32,
19258 #[doc = "Y Speed"]
19259 pub vy: f32,
19260 #[doc = "Z Speed"]
19261 pub vz: f32,
19262 #[doc = "X Acceleration"]
19263 pub ax: f32,
19264 #[doc = "Y Acceleration"]
19265 pub ay: f32,
19266 #[doc = "Z Acceleration"]
19267 pub az: f32,
19268 #[doc = "Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array."]
19269 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
19270 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
19271 pub covariance: [f32; 45],
19272 #[doc = "Class id of the estimator this estimate originated from."]
19273 pub estimator_type: MavEstimatorType,
19274}
19275impl LOCAL_POSITION_NED_COV_DATA {
19276 pub const ENCODED_LEN: usize = 225usize;
19277 pub const DEFAULT: Self = Self {
19278 time_usec: 0_u64,
19279 x: 0.0_f32,
19280 y: 0.0_f32,
19281 z: 0.0_f32,
19282 vx: 0.0_f32,
19283 vy: 0.0_f32,
19284 vz: 0.0_f32,
19285 ax: 0.0_f32,
19286 ay: 0.0_f32,
19287 az: 0.0_f32,
19288 covariance: [0.0_f32; 45usize],
19289 estimator_type: MavEstimatorType::DEFAULT,
19290 };
19291 #[cfg(feature = "arbitrary")]
19292 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19293 use arbitrary::{Arbitrary, Unstructured};
19294 let mut buf = [0u8; 1024];
19295 rng.fill_bytes(&mut buf);
19296 let mut unstructured = Unstructured::new(&buf);
19297 Self::arbitrary(&mut unstructured).unwrap_or_default()
19298 }
19299}
19300impl Default for LOCAL_POSITION_NED_COV_DATA {
19301 fn default() -> Self {
19302 Self::DEFAULT.clone()
19303 }
19304}
19305impl MessageData for LOCAL_POSITION_NED_COV_DATA {
19306 type Message = MavMessage;
19307 const ID: u32 = 64u32;
19308 const NAME: &'static str = "LOCAL_POSITION_NED_COV";
19309 const EXTRA_CRC: u8 = 191u8;
19310 const ENCODED_LEN: usize = 225usize;
19311 fn deser(
19312 _version: MavlinkVersion,
19313 __input: &[u8],
19314 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19315 let avail_len = __input.len();
19316 let mut payload_buf = [0; Self::ENCODED_LEN];
19317 let mut buf = if avail_len < Self::ENCODED_LEN {
19318 payload_buf[0..avail_len].copy_from_slice(__input);
19319 Bytes::new(&payload_buf)
19320 } else {
19321 Bytes::new(__input)
19322 };
19323 let mut __struct = Self::default();
19324 __struct.time_usec = buf.get_u64_le()?;
19325 __struct.x = buf.get_f32_le()?;
19326 __struct.y = buf.get_f32_le()?;
19327 __struct.z = buf.get_f32_le()?;
19328 __struct.vx = buf.get_f32_le()?;
19329 __struct.vy = buf.get_f32_le()?;
19330 __struct.vz = buf.get_f32_le()?;
19331 __struct.ax = buf.get_f32_le()?;
19332 __struct.ay = buf.get_f32_le()?;
19333 __struct.az = buf.get_f32_le()?;
19334 for v in &mut __struct.covariance {
19335 let val = buf.get_f32_le()?;
19336 *v = val;
19337 }
19338 let tmp = buf.get_u8()?;
19339 __struct.estimator_type =
19340 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19341 enum_type: "MavEstimatorType",
19342 value: tmp as u64,
19343 })?;
19344 Ok(__struct)
19345 }
19346 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19347 let mut __tmp = BytesMut::new(bytes);
19348 #[allow(clippy::absurd_extreme_comparisons)]
19349 #[allow(unused_comparisons)]
19350 if __tmp.remaining() < Self::ENCODED_LEN {
19351 panic!(
19352 "buffer is too small (need {} bytes, but got {})",
19353 Self::ENCODED_LEN,
19354 __tmp.remaining(),
19355 )
19356 }
19357 __tmp.put_u64_le(self.time_usec);
19358 __tmp.put_f32_le(self.x);
19359 __tmp.put_f32_le(self.y);
19360 __tmp.put_f32_le(self.z);
19361 __tmp.put_f32_le(self.vx);
19362 __tmp.put_f32_le(self.vy);
19363 __tmp.put_f32_le(self.vz);
19364 __tmp.put_f32_le(self.ax);
19365 __tmp.put_f32_le(self.ay);
19366 __tmp.put_f32_le(self.az);
19367 for val in &self.covariance {
19368 __tmp.put_f32_le(*val);
19369 }
19370 __tmp.put_u8(self.estimator_type as u8);
19371 if matches!(version, MavlinkVersion::V2) {
19372 let len = __tmp.len();
19373 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19374 } else {
19375 __tmp.len()
19376 }
19377 }
19378}
19379#[doc = "The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)."]
19380#[doc = ""]
19381#[doc = "ID: 89"]
19382#[derive(Debug, Clone, PartialEq)]
19383#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19384#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19385#[cfg_attr(feature = "ts", derive(TS))]
19386#[cfg_attr(feature = "ts", ts(export))]
19387pub struct LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA {
19388 #[doc = "Timestamp (time since system boot)."]
19389 pub time_boot_ms: u32,
19390 #[doc = "X Position"]
19391 pub x: f32,
19392 #[doc = "Y Position"]
19393 pub y: f32,
19394 #[doc = "Z Position"]
19395 pub z: f32,
19396 #[doc = "Roll"]
19397 pub roll: f32,
19398 #[doc = "Pitch"]
19399 pub pitch: f32,
19400 #[doc = "Yaw"]
19401 pub yaw: f32,
19402}
19403impl LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA {
19404 pub const ENCODED_LEN: usize = 28usize;
19405 pub const DEFAULT: Self = Self {
19406 time_boot_ms: 0_u32,
19407 x: 0.0_f32,
19408 y: 0.0_f32,
19409 z: 0.0_f32,
19410 roll: 0.0_f32,
19411 pitch: 0.0_f32,
19412 yaw: 0.0_f32,
19413 };
19414 #[cfg(feature = "arbitrary")]
19415 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19416 use arbitrary::{Arbitrary, Unstructured};
19417 let mut buf = [0u8; 1024];
19418 rng.fill_bytes(&mut buf);
19419 let mut unstructured = Unstructured::new(&buf);
19420 Self::arbitrary(&mut unstructured).unwrap_or_default()
19421 }
19422}
19423impl Default for LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA {
19424 fn default() -> Self {
19425 Self::DEFAULT.clone()
19426 }
19427}
19428impl MessageData for LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA {
19429 type Message = MavMessage;
19430 const ID: u32 = 89u32;
19431 const NAME: &'static str = "LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET";
19432 const EXTRA_CRC: u8 = 231u8;
19433 const ENCODED_LEN: usize = 28usize;
19434 fn deser(
19435 _version: MavlinkVersion,
19436 __input: &[u8],
19437 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19438 let avail_len = __input.len();
19439 let mut payload_buf = [0; Self::ENCODED_LEN];
19440 let mut buf = if avail_len < Self::ENCODED_LEN {
19441 payload_buf[0..avail_len].copy_from_slice(__input);
19442 Bytes::new(&payload_buf)
19443 } else {
19444 Bytes::new(__input)
19445 };
19446 let mut __struct = Self::default();
19447 __struct.time_boot_ms = buf.get_u32_le()?;
19448 __struct.x = buf.get_f32_le()?;
19449 __struct.y = buf.get_f32_le()?;
19450 __struct.z = buf.get_f32_le()?;
19451 __struct.roll = buf.get_f32_le()?;
19452 __struct.pitch = buf.get_f32_le()?;
19453 __struct.yaw = buf.get_f32_le()?;
19454 Ok(__struct)
19455 }
19456 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19457 let mut __tmp = BytesMut::new(bytes);
19458 #[allow(clippy::absurd_extreme_comparisons)]
19459 #[allow(unused_comparisons)]
19460 if __tmp.remaining() < Self::ENCODED_LEN {
19461 panic!(
19462 "buffer is too small (need {} bytes, but got {})",
19463 Self::ENCODED_LEN,
19464 __tmp.remaining(),
19465 )
19466 }
19467 __tmp.put_u32_le(self.time_boot_ms);
19468 __tmp.put_f32_le(self.x);
19469 __tmp.put_f32_le(self.y);
19470 __tmp.put_f32_le(self.z);
19471 __tmp.put_f32_le(self.roll);
19472 __tmp.put_f32_le(self.pitch);
19473 __tmp.put_f32_le(self.yaw);
19474 if matches!(version, MavlinkVersion::V2) {
19475 let len = __tmp.len();
19476 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19477 } else {
19478 __tmp.len()
19479 }
19480 }
19481}
19482#[doc = "An ack for a LOGGING_DATA_ACKED message."]
19483#[doc = ""]
19484#[doc = "ID: 268"]
19485#[derive(Debug, Clone, PartialEq)]
19486#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19487#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19488#[cfg_attr(feature = "ts", derive(TS))]
19489#[cfg_attr(feature = "ts", ts(export))]
19490pub struct LOGGING_ACK_DATA {
19491 #[doc = "sequence number (must match the one in LOGGING_DATA_ACKED)"]
19492 pub sequence: u16,
19493 #[doc = "system ID of the target"]
19494 pub target_system: u8,
19495 #[doc = "component ID of the target"]
19496 pub target_component: u8,
19497}
19498impl LOGGING_ACK_DATA {
19499 pub const ENCODED_LEN: usize = 4usize;
19500 pub const DEFAULT: Self = Self {
19501 sequence: 0_u16,
19502 target_system: 0_u8,
19503 target_component: 0_u8,
19504 };
19505 #[cfg(feature = "arbitrary")]
19506 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19507 use arbitrary::{Arbitrary, Unstructured};
19508 let mut buf = [0u8; 1024];
19509 rng.fill_bytes(&mut buf);
19510 let mut unstructured = Unstructured::new(&buf);
19511 Self::arbitrary(&mut unstructured).unwrap_or_default()
19512 }
19513}
19514impl Default for LOGGING_ACK_DATA {
19515 fn default() -> Self {
19516 Self::DEFAULT.clone()
19517 }
19518}
19519impl MessageData for LOGGING_ACK_DATA {
19520 type Message = MavMessage;
19521 const ID: u32 = 268u32;
19522 const NAME: &'static str = "LOGGING_ACK";
19523 const EXTRA_CRC: u8 = 14u8;
19524 const ENCODED_LEN: usize = 4usize;
19525 fn deser(
19526 _version: MavlinkVersion,
19527 __input: &[u8],
19528 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19529 let avail_len = __input.len();
19530 let mut payload_buf = [0; Self::ENCODED_LEN];
19531 let mut buf = if avail_len < Self::ENCODED_LEN {
19532 payload_buf[0..avail_len].copy_from_slice(__input);
19533 Bytes::new(&payload_buf)
19534 } else {
19535 Bytes::new(__input)
19536 };
19537 let mut __struct = Self::default();
19538 __struct.sequence = buf.get_u16_le()?;
19539 __struct.target_system = buf.get_u8()?;
19540 __struct.target_component = buf.get_u8()?;
19541 Ok(__struct)
19542 }
19543 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19544 let mut __tmp = BytesMut::new(bytes);
19545 #[allow(clippy::absurd_extreme_comparisons)]
19546 #[allow(unused_comparisons)]
19547 if __tmp.remaining() < Self::ENCODED_LEN {
19548 panic!(
19549 "buffer is too small (need {} bytes, but got {})",
19550 Self::ENCODED_LEN,
19551 __tmp.remaining(),
19552 )
19553 }
19554 __tmp.put_u16_le(self.sequence);
19555 __tmp.put_u8(self.target_system);
19556 __tmp.put_u8(self.target_component);
19557 if matches!(version, MavlinkVersion::V2) {
19558 let len = __tmp.len();
19559 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19560 } else {
19561 __tmp.len()
19562 }
19563 }
19564}
19565#[doc = "A message containing logged data (see also MAV_CMD_LOGGING_START)."]
19566#[doc = ""]
19567#[doc = "ID: 266"]
19568#[derive(Debug, Clone, PartialEq)]
19569#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19570#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19571#[cfg_attr(feature = "ts", derive(TS))]
19572#[cfg_attr(feature = "ts", ts(export))]
19573pub struct LOGGING_DATA_DATA {
19574 #[doc = "sequence number (can wrap)"]
19575 pub sequence: u16,
19576 #[doc = "system ID of the target"]
19577 pub target_system: u8,
19578 #[doc = "component ID of the target"]
19579 pub target_component: u8,
19580 #[doc = "data length"]
19581 pub length: u8,
19582 #[doc = "offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists)."]
19583 pub first_message_offset: u8,
19584 #[doc = "logged data"]
19585 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
19586 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
19587 pub data: [u8; 249],
19588}
19589impl LOGGING_DATA_DATA {
19590 pub const ENCODED_LEN: usize = 255usize;
19591 pub const DEFAULT: Self = Self {
19592 sequence: 0_u16,
19593 target_system: 0_u8,
19594 target_component: 0_u8,
19595 length: 0_u8,
19596 first_message_offset: 0_u8,
19597 data: [0_u8; 249usize],
19598 };
19599 #[cfg(feature = "arbitrary")]
19600 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19601 use arbitrary::{Arbitrary, Unstructured};
19602 let mut buf = [0u8; 1024];
19603 rng.fill_bytes(&mut buf);
19604 let mut unstructured = Unstructured::new(&buf);
19605 Self::arbitrary(&mut unstructured).unwrap_or_default()
19606 }
19607}
19608impl Default for LOGGING_DATA_DATA {
19609 fn default() -> Self {
19610 Self::DEFAULT.clone()
19611 }
19612}
19613impl MessageData for LOGGING_DATA_DATA {
19614 type Message = MavMessage;
19615 const ID: u32 = 266u32;
19616 const NAME: &'static str = "LOGGING_DATA";
19617 const EXTRA_CRC: u8 = 193u8;
19618 const ENCODED_LEN: usize = 255usize;
19619 fn deser(
19620 _version: MavlinkVersion,
19621 __input: &[u8],
19622 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19623 let avail_len = __input.len();
19624 let mut payload_buf = [0; Self::ENCODED_LEN];
19625 let mut buf = if avail_len < Self::ENCODED_LEN {
19626 payload_buf[0..avail_len].copy_from_slice(__input);
19627 Bytes::new(&payload_buf)
19628 } else {
19629 Bytes::new(__input)
19630 };
19631 let mut __struct = Self::default();
19632 __struct.sequence = buf.get_u16_le()?;
19633 __struct.target_system = buf.get_u8()?;
19634 __struct.target_component = buf.get_u8()?;
19635 __struct.length = buf.get_u8()?;
19636 __struct.first_message_offset = buf.get_u8()?;
19637 for v in &mut __struct.data {
19638 let val = buf.get_u8()?;
19639 *v = val;
19640 }
19641 Ok(__struct)
19642 }
19643 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19644 let mut __tmp = BytesMut::new(bytes);
19645 #[allow(clippy::absurd_extreme_comparisons)]
19646 #[allow(unused_comparisons)]
19647 if __tmp.remaining() < Self::ENCODED_LEN {
19648 panic!(
19649 "buffer is too small (need {} bytes, but got {})",
19650 Self::ENCODED_LEN,
19651 __tmp.remaining(),
19652 )
19653 }
19654 __tmp.put_u16_le(self.sequence);
19655 __tmp.put_u8(self.target_system);
19656 __tmp.put_u8(self.target_component);
19657 __tmp.put_u8(self.length);
19658 __tmp.put_u8(self.first_message_offset);
19659 for val in &self.data {
19660 __tmp.put_u8(*val);
19661 }
19662 if matches!(version, MavlinkVersion::V2) {
19663 let len = __tmp.len();
19664 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19665 } else {
19666 __tmp.len()
19667 }
19668 }
19669}
19670#[doc = "A message containing logged data which requires a LOGGING_ACK to be sent back."]
19671#[doc = ""]
19672#[doc = "ID: 267"]
19673#[derive(Debug, Clone, PartialEq)]
19674#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19675#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19676#[cfg_attr(feature = "ts", derive(TS))]
19677#[cfg_attr(feature = "ts", ts(export))]
19678pub struct LOGGING_DATA_ACKED_DATA {
19679 #[doc = "sequence number (can wrap)"]
19680 pub sequence: u16,
19681 #[doc = "system ID of the target"]
19682 pub target_system: u8,
19683 #[doc = "component ID of the target"]
19684 pub target_component: u8,
19685 #[doc = "data length"]
19686 pub length: u8,
19687 #[doc = "offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists)."]
19688 pub first_message_offset: u8,
19689 #[doc = "logged data"]
19690 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
19691 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
19692 pub data: [u8; 249],
19693}
19694impl LOGGING_DATA_ACKED_DATA {
19695 pub const ENCODED_LEN: usize = 255usize;
19696 pub const DEFAULT: Self = Self {
19697 sequence: 0_u16,
19698 target_system: 0_u8,
19699 target_component: 0_u8,
19700 length: 0_u8,
19701 first_message_offset: 0_u8,
19702 data: [0_u8; 249usize],
19703 };
19704 #[cfg(feature = "arbitrary")]
19705 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19706 use arbitrary::{Arbitrary, Unstructured};
19707 let mut buf = [0u8; 1024];
19708 rng.fill_bytes(&mut buf);
19709 let mut unstructured = Unstructured::new(&buf);
19710 Self::arbitrary(&mut unstructured).unwrap_or_default()
19711 }
19712}
19713impl Default for LOGGING_DATA_ACKED_DATA {
19714 fn default() -> Self {
19715 Self::DEFAULT.clone()
19716 }
19717}
19718impl MessageData for LOGGING_DATA_ACKED_DATA {
19719 type Message = MavMessage;
19720 const ID: u32 = 267u32;
19721 const NAME: &'static str = "LOGGING_DATA_ACKED";
19722 const EXTRA_CRC: u8 = 35u8;
19723 const ENCODED_LEN: usize = 255usize;
19724 fn deser(
19725 _version: MavlinkVersion,
19726 __input: &[u8],
19727 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19728 let avail_len = __input.len();
19729 let mut payload_buf = [0; Self::ENCODED_LEN];
19730 let mut buf = if avail_len < Self::ENCODED_LEN {
19731 payload_buf[0..avail_len].copy_from_slice(__input);
19732 Bytes::new(&payload_buf)
19733 } else {
19734 Bytes::new(__input)
19735 };
19736 let mut __struct = Self::default();
19737 __struct.sequence = buf.get_u16_le()?;
19738 __struct.target_system = buf.get_u8()?;
19739 __struct.target_component = buf.get_u8()?;
19740 __struct.length = buf.get_u8()?;
19741 __struct.first_message_offset = buf.get_u8()?;
19742 for v in &mut __struct.data {
19743 let val = buf.get_u8()?;
19744 *v = val;
19745 }
19746 Ok(__struct)
19747 }
19748 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19749 let mut __tmp = BytesMut::new(bytes);
19750 #[allow(clippy::absurd_extreme_comparisons)]
19751 #[allow(unused_comparisons)]
19752 if __tmp.remaining() < Self::ENCODED_LEN {
19753 panic!(
19754 "buffer is too small (need {} bytes, but got {})",
19755 Self::ENCODED_LEN,
19756 __tmp.remaining(),
19757 )
19758 }
19759 __tmp.put_u16_le(self.sequence);
19760 __tmp.put_u8(self.target_system);
19761 __tmp.put_u8(self.target_component);
19762 __tmp.put_u8(self.length);
19763 __tmp.put_u8(self.first_message_offset);
19764 for val in &self.data {
19765 __tmp.put_u8(*val);
19766 }
19767 if matches!(version, MavlinkVersion::V2) {
19768 let len = __tmp.len();
19769 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19770 } else {
19771 __tmp.len()
19772 }
19773 }
19774}
19775#[doc = "Reply to LOG_REQUEST_DATA."]
19776#[doc = ""]
19777#[doc = "ID: 120"]
19778#[derive(Debug, Clone, PartialEq)]
19779#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19780#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19781#[cfg_attr(feature = "ts", derive(TS))]
19782#[cfg_attr(feature = "ts", ts(export))]
19783pub struct LOG_DATA_DATA {
19784 #[doc = "Offset into the log"]
19785 pub ofs: u32,
19786 #[doc = "Log id (from LOG_ENTRY reply)"]
19787 pub id: u16,
19788 #[doc = "Number of bytes (zero for end of log)"]
19789 pub count: u8,
19790 #[doc = "log data"]
19791 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
19792 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
19793 pub data: [u8; 90],
19794}
19795impl LOG_DATA_DATA {
19796 pub const ENCODED_LEN: usize = 97usize;
19797 pub const DEFAULT: Self = Self {
19798 ofs: 0_u32,
19799 id: 0_u16,
19800 count: 0_u8,
19801 data: [0_u8; 90usize],
19802 };
19803 #[cfg(feature = "arbitrary")]
19804 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19805 use arbitrary::{Arbitrary, Unstructured};
19806 let mut buf = [0u8; 1024];
19807 rng.fill_bytes(&mut buf);
19808 let mut unstructured = Unstructured::new(&buf);
19809 Self::arbitrary(&mut unstructured).unwrap_or_default()
19810 }
19811}
19812impl Default for LOG_DATA_DATA {
19813 fn default() -> Self {
19814 Self::DEFAULT.clone()
19815 }
19816}
19817impl MessageData for LOG_DATA_DATA {
19818 type Message = MavMessage;
19819 const ID: u32 = 120u32;
19820 const NAME: &'static str = "LOG_DATA";
19821 const EXTRA_CRC: u8 = 134u8;
19822 const ENCODED_LEN: usize = 97usize;
19823 fn deser(
19824 _version: MavlinkVersion,
19825 __input: &[u8],
19826 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19827 let avail_len = __input.len();
19828 let mut payload_buf = [0; Self::ENCODED_LEN];
19829 let mut buf = if avail_len < Self::ENCODED_LEN {
19830 payload_buf[0..avail_len].copy_from_slice(__input);
19831 Bytes::new(&payload_buf)
19832 } else {
19833 Bytes::new(__input)
19834 };
19835 let mut __struct = Self::default();
19836 __struct.ofs = buf.get_u32_le()?;
19837 __struct.id = buf.get_u16_le()?;
19838 __struct.count = buf.get_u8()?;
19839 for v in &mut __struct.data {
19840 let val = buf.get_u8()?;
19841 *v = val;
19842 }
19843 Ok(__struct)
19844 }
19845 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19846 let mut __tmp = BytesMut::new(bytes);
19847 #[allow(clippy::absurd_extreme_comparisons)]
19848 #[allow(unused_comparisons)]
19849 if __tmp.remaining() < Self::ENCODED_LEN {
19850 panic!(
19851 "buffer is too small (need {} bytes, but got {})",
19852 Self::ENCODED_LEN,
19853 __tmp.remaining(),
19854 )
19855 }
19856 __tmp.put_u32_le(self.ofs);
19857 __tmp.put_u16_le(self.id);
19858 __tmp.put_u8(self.count);
19859 for val in &self.data {
19860 __tmp.put_u8(*val);
19861 }
19862 if matches!(version, MavlinkVersion::V2) {
19863 let len = __tmp.len();
19864 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19865 } else {
19866 __tmp.len()
19867 }
19868 }
19869}
19870#[doc = "Reply to LOG_REQUEST_LIST."]
19871#[doc = ""]
19872#[doc = "ID: 118"]
19873#[derive(Debug, Clone, PartialEq)]
19874#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19875#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19876#[cfg_attr(feature = "ts", derive(TS))]
19877#[cfg_attr(feature = "ts", ts(export))]
19878pub struct LOG_ENTRY_DATA {
19879 #[doc = "UTC timestamp of log since 1970, or 0 if not available"]
19880 pub time_utc: u32,
19881 #[doc = "Size of the log (may be approximate)"]
19882 pub size: u32,
19883 #[doc = "Log id"]
19884 pub id: u16,
19885 #[doc = "Total number of logs"]
19886 pub num_logs: u16,
19887 #[doc = "High log number"]
19888 pub last_log_num: u16,
19889}
19890impl LOG_ENTRY_DATA {
19891 pub const ENCODED_LEN: usize = 14usize;
19892 pub const DEFAULT: Self = Self {
19893 time_utc: 0_u32,
19894 size: 0_u32,
19895 id: 0_u16,
19896 num_logs: 0_u16,
19897 last_log_num: 0_u16,
19898 };
19899 #[cfg(feature = "arbitrary")]
19900 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19901 use arbitrary::{Arbitrary, Unstructured};
19902 let mut buf = [0u8; 1024];
19903 rng.fill_bytes(&mut buf);
19904 let mut unstructured = Unstructured::new(&buf);
19905 Self::arbitrary(&mut unstructured).unwrap_or_default()
19906 }
19907}
19908impl Default for LOG_ENTRY_DATA {
19909 fn default() -> Self {
19910 Self::DEFAULT.clone()
19911 }
19912}
19913impl MessageData for LOG_ENTRY_DATA {
19914 type Message = MavMessage;
19915 const ID: u32 = 118u32;
19916 const NAME: &'static str = "LOG_ENTRY";
19917 const EXTRA_CRC: u8 = 56u8;
19918 const ENCODED_LEN: usize = 14usize;
19919 fn deser(
19920 _version: MavlinkVersion,
19921 __input: &[u8],
19922 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19923 let avail_len = __input.len();
19924 let mut payload_buf = [0; Self::ENCODED_LEN];
19925 let mut buf = if avail_len < Self::ENCODED_LEN {
19926 payload_buf[0..avail_len].copy_from_slice(__input);
19927 Bytes::new(&payload_buf)
19928 } else {
19929 Bytes::new(__input)
19930 };
19931 let mut __struct = Self::default();
19932 __struct.time_utc = buf.get_u32_le()?;
19933 __struct.size = buf.get_u32_le()?;
19934 __struct.id = buf.get_u16_le()?;
19935 __struct.num_logs = buf.get_u16_le()?;
19936 __struct.last_log_num = buf.get_u16_le()?;
19937 Ok(__struct)
19938 }
19939 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19940 let mut __tmp = BytesMut::new(bytes);
19941 #[allow(clippy::absurd_extreme_comparisons)]
19942 #[allow(unused_comparisons)]
19943 if __tmp.remaining() < Self::ENCODED_LEN {
19944 panic!(
19945 "buffer is too small (need {} bytes, but got {})",
19946 Self::ENCODED_LEN,
19947 __tmp.remaining(),
19948 )
19949 }
19950 __tmp.put_u32_le(self.time_utc);
19951 __tmp.put_u32_le(self.size);
19952 __tmp.put_u16_le(self.id);
19953 __tmp.put_u16_le(self.num_logs);
19954 __tmp.put_u16_le(self.last_log_num);
19955 if matches!(version, MavlinkVersion::V2) {
19956 let len = __tmp.len();
19957 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19958 } else {
19959 __tmp.len()
19960 }
19961 }
19962}
19963#[doc = "Erase all logs."]
19964#[doc = ""]
19965#[doc = "ID: 121"]
19966#[derive(Debug, Clone, PartialEq)]
19967#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19968#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19969#[cfg_attr(feature = "ts", derive(TS))]
19970#[cfg_attr(feature = "ts", ts(export))]
19971pub struct LOG_ERASE_DATA {
19972 #[doc = "System ID"]
19973 pub target_system: u8,
19974 #[doc = "Component ID"]
19975 pub target_component: u8,
19976}
19977impl LOG_ERASE_DATA {
19978 pub const ENCODED_LEN: usize = 2usize;
19979 pub const DEFAULT: Self = Self {
19980 target_system: 0_u8,
19981 target_component: 0_u8,
19982 };
19983 #[cfg(feature = "arbitrary")]
19984 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19985 use arbitrary::{Arbitrary, Unstructured};
19986 let mut buf = [0u8; 1024];
19987 rng.fill_bytes(&mut buf);
19988 let mut unstructured = Unstructured::new(&buf);
19989 Self::arbitrary(&mut unstructured).unwrap_or_default()
19990 }
19991}
19992impl Default for LOG_ERASE_DATA {
19993 fn default() -> Self {
19994 Self::DEFAULT.clone()
19995 }
19996}
19997impl MessageData for LOG_ERASE_DATA {
19998 type Message = MavMessage;
19999 const ID: u32 = 121u32;
20000 const NAME: &'static str = "LOG_ERASE";
20001 const EXTRA_CRC: u8 = 237u8;
20002 const ENCODED_LEN: usize = 2usize;
20003 fn deser(
20004 _version: MavlinkVersion,
20005 __input: &[u8],
20006 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20007 let avail_len = __input.len();
20008 let mut payload_buf = [0; Self::ENCODED_LEN];
20009 let mut buf = if avail_len < Self::ENCODED_LEN {
20010 payload_buf[0..avail_len].copy_from_slice(__input);
20011 Bytes::new(&payload_buf)
20012 } else {
20013 Bytes::new(__input)
20014 };
20015 let mut __struct = Self::default();
20016 __struct.target_system = buf.get_u8()?;
20017 __struct.target_component = buf.get_u8()?;
20018 Ok(__struct)
20019 }
20020 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20021 let mut __tmp = BytesMut::new(bytes);
20022 #[allow(clippy::absurd_extreme_comparisons)]
20023 #[allow(unused_comparisons)]
20024 if __tmp.remaining() < Self::ENCODED_LEN {
20025 panic!(
20026 "buffer is too small (need {} bytes, but got {})",
20027 Self::ENCODED_LEN,
20028 __tmp.remaining(),
20029 )
20030 }
20031 __tmp.put_u8(self.target_system);
20032 __tmp.put_u8(self.target_component);
20033 if matches!(version, MavlinkVersion::V2) {
20034 let len = __tmp.len();
20035 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20036 } else {
20037 __tmp.len()
20038 }
20039 }
20040}
20041#[doc = "Request a chunk of a log."]
20042#[doc = ""]
20043#[doc = "ID: 119"]
20044#[derive(Debug, Clone, PartialEq)]
20045#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20046#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20047#[cfg_attr(feature = "ts", derive(TS))]
20048#[cfg_attr(feature = "ts", ts(export))]
20049pub struct LOG_REQUEST_DATA_DATA {
20050 #[doc = "Offset into the log"]
20051 pub ofs: u32,
20052 #[doc = "Number of bytes"]
20053 pub count: u32,
20054 #[doc = "Log id (from LOG_ENTRY reply)"]
20055 pub id: u16,
20056 #[doc = "System ID"]
20057 pub target_system: u8,
20058 #[doc = "Component ID"]
20059 pub target_component: u8,
20060}
20061impl LOG_REQUEST_DATA_DATA {
20062 pub const ENCODED_LEN: usize = 12usize;
20063 pub const DEFAULT: Self = Self {
20064 ofs: 0_u32,
20065 count: 0_u32,
20066 id: 0_u16,
20067 target_system: 0_u8,
20068 target_component: 0_u8,
20069 };
20070 #[cfg(feature = "arbitrary")]
20071 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20072 use arbitrary::{Arbitrary, Unstructured};
20073 let mut buf = [0u8; 1024];
20074 rng.fill_bytes(&mut buf);
20075 let mut unstructured = Unstructured::new(&buf);
20076 Self::arbitrary(&mut unstructured).unwrap_or_default()
20077 }
20078}
20079impl Default for LOG_REQUEST_DATA_DATA {
20080 fn default() -> Self {
20081 Self::DEFAULT.clone()
20082 }
20083}
20084impl MessageData for LOG_REQUEST_DATA_DATA {
20085 type Message = MavMessage;
20086 const ID: u32 = 119u32;
20087 const NAME: &'static str = "LOG_REQUEST_DATA";
20088 const EXTRA_CRC: u8 = 116u8;
20089 const ENCODED_LEN: usize = 12usize;
20090 fn deser(
20091 _version: MavlinkVersion,
20092 __input: &[u8],
20093 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20094 let avail_len = __input.len();
20095 let mut payload_buf = [0; Self::ENCODED_LEN];
20096 let mut buf = if avail_len < Self::ENCODED_LEN {
20097 payload_buf[0..avail_len].copy_from_slice(__input);
20098 Bytes::new(&payload_buf)
20099 } else {
20100 Bytes::new(__input)
20101 };
20102 let mut __struct = Self::default();
20103 __struct.ofs = buf.get_u32_le()?;
20104 __struct.count = buf.get_u32_le()?;
20105 __struct.id = buf.get_u16_le()?;
20106 __struct.target_system = buf.get_u8()?;
20107 __struct.target_component = buf.get_u8()?;
20108 Ok(__struct)
20109 }
20110 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20111 let mut __tmp = BytesMut::new(bytes);
20112 #[allow(clippy::absurd_extreme_comparisons)]
20113 #[allow(unused_comparisons)]
20114 if __tmp.remaining() < Self::ENCODED_LEN {
20115 panic!(
20116 "buffer is too small (need {} bytes, but got {})",
20117 Self::ENCODED_LEN,
20118 __tmp.remaining(),
20119 )
20120 }
20121 __tmp.put_u32_le(self.ofs);
20122 __tmp.put_u32_le(self.count);
20123 __tmp.put_u16_le(self.id);
20124 __tmp.put_u8(self.target_system);
20125 __tmp.put_u8(self.target_component);
20126 if matches!(version, MavlinkVersion::V2) {
20127 let len = __tmp.len();
20128 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20129 } else {
20130 __tmp.len()
20131 }
20132 }
20133}
20134#[doc = "Stop log transfer and resume normal logging."]
20135#[doc = ""]
20136#[doc = "ID: 122"]
20137#[derive(Debug, Clone, PartialEq)]
20138#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20139#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20140#[cfg_attr(feature = "ts", derive(TS))]
20141#[cfg_attr(feature = "ts", ts(export))]
20142pub struct LOG_REQUEST_END_DATA {
20143 #[doc = "System ID"]
20144 pub target_system: u8,
20145 #[doc = "Component ID"]
20146 pub target_component: u8,
20147}
20148impl LOG_REQUEST_END_DATA {
20149 pub const ENCODED_LEN: usize = 2usize;
20150 pub const DEFAULT: Self = Self {
20151 target_system: 0_u8,
20152 target_component: 0_u8,
20153 };
20154 #[cfg(feature = "arbitrary")]
20155 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20156 use arbitrary::{Arbitrary, Unstructured};
20157 let mut buf = [0u8; 1024];
20158 rng.fill_bytes(&mut buf);
20159 let mut unstructured = Unstructured::new(&buf);
20160 Self::arbitrary(&mut unstructured).unwrap_or_default()
20161 }
20162}
20163impl Default for LOG_REQUEST_END_DATA {
20164 fn default() -> Self {
20165 Self::DEFAULT.clone()
20166 }
20167}
20168impl MessageData for LOG_REQUEST_END_DATA {
20169 type Message = MavMessage;
20170 const ID: u32 = 122u32;
20171 const NAME: &'static str = "LOG_REQUEST_END";
20172 const EXTRA_CRC: u8 = 203u8;
20173 const ENCODED_LEN: usize = 2usize;
20174 fn deser(
20175 _version: MavlinkVersion,
20176 __input: &[u8],
20177 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20178 let avail_len = __input.len();
20179 let mut payload_buf = [0; Self::ENCODED_LEN];
20180 let mut buf = if avail_len < Self::ENCODED_LEN {
20181 payload_buf[0..avail_len].copy_from_slice(__input);
20182 Bytes::new(&payload_buf)
20183 } else {
20184 Bytes::new(__input)
20185 };
20186 let mut __struct = Self::default();
20187 __struct.target_system = buf.get_u8()?;
20188 __struct.target_component = buf.get_u8()?;
20189 Ok(__struct)
20190 }
20191 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20192 let mut __tmp = BytesMut::new(bytes);
20193 #[allow(clippy::absurd_extreme_comparisons)]
20194 #[allow(unused_comparisons)]
20195 if __tmp.remaining() < Self::ENCODED_LEN {
20196 panic!(
20197 "buffer is too small (need {} bytes, but got {})",
20198 Self::ENCODED_LEN,
20199 __tmp.remaining(),
20200 )
20201 }
20202 __tmp.put_u8(self.target_system);
20203 __tmp.put_u8(self.target_component);
20204 if matches!(version, MavlinkVersion::V2) {
20205 let len = __tmp.len();
20206 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20207 } else {
20208 __tmp.len()
20209 }
20210 }
20211}
20212#[doc = "Request a list of available logs. On some systems calling this may stop on-board logging until LOG_REQUEST_END is called. If there are no log files available this request shall be answered with one LOG_ENTRY message with id = 0 and num_logs = 0."]
20213#[doc = ""]
20214#[doc = "ID: 117"]
20215#[derive(Debug, Clone, PartialEq)]
20216#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20217#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20218#[cfg_attr(feature = "ts", derive(TS))]
20219#[cfg_attr(feature = "ts", ts(export))]
20220pub struct LOG_REQUEST_LIST_DATA {
20221 #[doc = "First log id (0 for first available)"]
20222 pub start: u16,
20223 #[doc = "Last log id (0xffff for last available)"]
20224 pub end: u16,
20225 #[doc = "System ID"]
20226 pub target_system: u8,
20227 #[doc = "Component ID"]
20228 pub target_component: u8,
20229}
20230impl LOG_REQUEST_LIST_DATA {
20231 pub const ENCODED_LEN: usize = 6usize;
20232 pub const DEFAULT: Self = Self {
20233 start: 0_u16,
20234 end: 0_u16,
20235 target_system: 0_u8,
20236 target_component: 0_u8,
20237 };
20238 #[cfg(feature = "arbitrary")]
20239 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20240 use arbitrary::{Arbitrary, Unstructured};
20241 let mut buf = [0u8; 1024];
20242 rng.fill_bytes(&mut buf);
20243 let mut unstructured = Unstructured::new(&buf);
20244 Self::arbitrary(&mut unstructured).unwrap_or_default()
20245 }
20246}
20247impl Default for LOG_REQUEST_LIST_DATA {
20248 fn default() -> Self {
20249 Self::DEFAULT.clone()
20250 }
20251}
20252impl MessageData for LOG_REQUEST_LIST_DATA {
20253 type Message = MavMessage;
20254 const ID: u32 = 117u32;
20255 const NAME: &'static str = "LOG_REQUEST_LIST";
20256 const EXTRA_CRC: u8 = 128u8;
20257 const ENCODED_LEN: usize = 6usize;
20258 fn deser(
20259 _version: MavlinkVersion,
20260 __input: &[u8],
20261 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20262 let avail_len = __input.len();
20263 let mut payload_buf = [0; Self::ENCODED_LEN];
20264 let mut buf = if avail_len < Self::ENCODED_LEN {
20265 payload_buf[0..avail_len].copy_from_slice(__input);
20266 Bytes::new(&payload_buf)
20267 } else {
20268 Bytes::new(__input)
20269 };
20270 let mut __struct = Self::default();
20271 __struct.start = buf.get_u16_le()?;
20272 __struct.end = buf.get_u16_le()?;
20273 __struct.target_system = buf.get_u8()?;
20274 __struct.target_component = buf.get_u8()?;
20275 Ok(__struct)
20276 }
20277 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20278 let mut __tmp = BytesMut::new(bytes);
20279 #[allow(clippy::absurd_extreme_comparisons)]
20280 #[allow(unused_comparisons)]
20281 if __tmp.remaining() < Self::ENCODED_LEN {
20282 panic!(
20283 "buffer is too small (need {} bytes, but got {})",
20284 Self::ENCODED_LEN,
20285 __tmp.remaining(),
20286 )
20287 }
20288 __tmp.put_u16_le(self.start);
20289 __tmp.put_u16_le(self.end);
20290 __tmp.put_u8(self.target_system);
20291 __tmp.put_u8(self.target_component);
20292 if matches!(version, MavlinkVersion::V2) {
20293 let len = __tmp.len();
20294 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20295 } else {
20296 __tmp.len()
20297 }
20298 }
20299}
20300#[doc = "Reports results of completed compass calibration. Sent until MAG_CAL_ACK received."]
20301#[doc = ""]
20302#[doc = "ID: 192"]
20303#[derive(Debug, Clone, PartialEq)]
20304#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20305#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20306#[cfg_attr(feature = "ts", derive(TS))]
20307#[cfg_attr(feature = "ts", ts(export))]
20308pub struct MAG_CAL_REPORT_DATA {
20309 #[doc = "RMS milligauss residuals."]
20310 pub fitness: f32,
20311 #[doc = "X offset."]
20312 pub ofs_x: f32,
20313 #[doc = "Y offset."]
20314 pub ofs_y: f32,
20315 #[doc = "Z offset."]
20316 pub ofs_z: f32,
20317 #[doc = "X diagonal (matrix 11)."]
20318 pub diag_x: f32,
20319 #[doc = "Y diagonal (matrix 22)."]
20320 pub diag_y: f32,
20321 #[doc = "Z diagonal (matrix 33)."]
20322 pub diag_z: f32,
20323 #[doc = "X off-diagonal (matrix 12 and 21)."]
20324 pub offdiag_x: f32,
20325 #[doc = "Y off-diagonal (matrix 13 and 31)."]
20326 pub offdiag_y: f32,
20327 #[doc = "Z off-diagonal (matrix 32 and 23)."]
20328 pub offdiag_z: f32,
20329 #[doc = "Compass being calibrated."]
20330 pub compass_id: u8,
20331 #[doc = "Bitmask of compasses being calibrated."]
20332 pub cal_mask: u8,
20333 #[doc = "Calibration Status."]
20334 pub cal_status: MagCalStatus,
20335 #[doc = "0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters."]
20336 pub autosaved: u8,
20337 #[doc = "Confidence in orientation (higher is better)."]
20338 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20339 pub orientation_confidence: f32,
20340 #[doc = "orientation before calibration."]
20341 #[cfg_attr(feature = "serde", serde(default))]
20342 pub old_orientation: MavSensorOrientation,
20343 #[doc = "orientation after calibration."]
20344 #[cfg_attr(feature = "serde", serde(default))]
20345 pub new_orientation: MavSensorOrientation,
20346 #[doc = "field radius correction factor"]
20347 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20348 pub scale_factor: f32,
20349}
20350impl MAG_CAL_REPORT_DATA {
20351 pub const ENCODED_LEN: usize = 54usize;
20352 pub const DEFAULT: Self = Self {
20353 fitness: 0.0_f32,
20354 ofs_x: 0.0_f32,
20355 ofs_y: 0.0_f32,
20356 ofs_z: 0.0_f32,
20357 diag_x: 0.0_f32,
20358 diag_y: 0.0_f32,
20359 diag_z: 0.0_f32,
20360 offdiag_x: 0.0_f32,
20361 offdiag_y: 0.0_f32,
20362 offdiag_z: 0.0_f32,
20363 compass_id: 0_u8,
20364 cal_mask: 0_u8,
20365 cal_status: MagCalStatus::DEFAULT,
20366 autosaved: 0_u8,
20367 orientation_confidence: 0.0_f32,
20368 old_orientation: MavSensorOrientation::DEFAULT,
20369 new_orientation: MavSensorOrientation::DEFAULT,
20370 scale_factor: 0.0_f32,
20371 };
20372 #[cfg(feature = "arbitrary")]
20373 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20374 use arbitrary::{Arbitrary, Unstructured};
20375 let mut buf = [0u8; 1024];
20376 rng.fill_bytes(&mut buf);
20377 let mut unstructured = Unstructured::new(&buf);
20378 Self::arbitrary(&mut unstructured).unwrap_or_default()
20379 }
20380}
20381impl Default for MAG_CAL_REPORT_DATA {
20382 fn default() -> Self {
20383 Self::DEFAULT.clone()
20384 }
20385}
20386impl MessageData for MAG_CAL_REPORT_DATA {
20387 type Message = MavMessage;
20388 const ID: u32 = 192u32;
20389 const NAME: &'static str = "MAG_CAL_REPORT";
20390 const EXTRA_CRC: u8 = 36u8;
20391 const ENCODED_LEN: usize = 54usize;
20392 fn deser(
20393 _version: MavlinkVersion,
20394 __input: &[u8],
20395 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20396 let avail_len = __input.len();
20397 let mut payload_buf = [0; Self::ENCODED_LEN];
20398 let mut buf = if avail_len < Self::ENCODED_LEN {
20399 payload_buf[0..avail_len].copy_from_slice(__input);
20400 Bytes::new(&payload_buf)
20401 } else {
20402 Bytes::new(__input)
20403 };
20404 let mut __struct = Self::default();
20405 __struct.fitness = buf.get_f32_le()?;
20406 __struct.ofs_x = buf.get_f32_le()?;
20407 __struct.ofs_y = buf.get_f32_le()?;
20408 __struct.ofs_z = buf.get_f32_le()?;
20409 __struct.diag_x = buf.get_f32_le()?;
20410 __struct.diag_y = buf.get_f32_le()?;
20411 __struct.diag_z = buf.get_f32_le()?;
20412 __struct.offdiag_x = buf.get_f32_le()?;
20413 __struct.offdiag_y = buf.get_f32_le()?;
20414 __struct.offdiag_z = buf.get_f32_le()?;
20415 __struct.compass_id = buf.get_u8()?;
20416 __struct.cal_mask = buf.get_u8()?;
20417 let tmp = buf.get_u8()?;
20418 __struct.cal_status =
20419 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
20420 enum_type: "MagCalStatus",
20421 value: tmp as u64,
20422 })?;
20423 __struct.autosaved = buf.get_u8()?;
20424 __struct.orientation_confidence = buf.get_f32_le()?;
20425 let tmp = buf.get_u8()?;
20426 __struct.old_orientation =
20427 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
20428 enum_type: "MavSensorOrientation",
20429 value: tmp as u64,
20430 })?;
20431 let tmp = buf.get_u8()?;
20432 __struct.new_orientation =
20433 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
20434 enum_type: "MavSensorOrientation",
20435 value: tmp as u64,
20436 })?;
20437 __struct.scale_factor = buf.get_f32_le()?;
20438 Ok(__struct)
20439 }
20440 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20441 let mut __tmp = BytesMut::new(bytes);
20442 #[allow(clippy::absurd_extreme_comparisons)]
20443 #[allow(unused_comparisons)]
20444 if __tmp.remaining() < Self::ENCODED_LEN {
20445 panic!(
20446 "buffer is too small (need {} bytes, but got {})",
20447 Self::ENCODED_LEN,
20448 __tmp.remaining(),
20449 )
20450 }
20451 __tmp.put_f32_le(self.fitness);
20452 __tmp.put_f32_le(self.ofs_x);
20453 __tmp.put_f32_le(self.ofs_y);
20454 __tmp.put_f32_le(self.ofs_z);
20455 __tmp.put_f32_le(self.diag_x);
20456 __tmp.put_f32_le(self.diag_y);
20457 __tmp.put_f32_le(self.diag_z);
20458 __tmp.put_f32_le(self.offdiag_x);
20459 __tmp.put_f32_le(self.offdiag_y);
20460 __tmp.put_f32_le(self.offdiag_z);
20461 __tmp.put_u8(self.compass_id);
20462 __tmp.put_u8(self.cal_mask);
20463 __tmp.put_u8(self.cal_status as u8);
20464 __tmp.put_u8(self.autosaved);
20465 if matches!(version, MavlinkVersion::V2) {
20466 __tmp.put_f32_le(self.orientation_confidence);
20467 __tmp.put_u8(self.old_orientation as u8);
20468 __tmp.put_u8(self.new_orientation as u8);
20469 __tmp.put_f32_le(self.scale_factor);
20470 let len = __tmp.len();
20471 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20472 } else {
20473 __tmp.len()
20474 }
20475 }
20476}
20477#[doc = "This message provides an API for manually controlling the vehicle using standard joystick axes nomenclature, along with a joystick-like input device. Unused axes can be disabled and buttons states are transmitted as individual on/off bits of a bitmask."]
20478#[doc = ""]
20479#[doc = "ID: 69"]
20480#[derive(Debug, Clone, PartialEq)]
20481#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20482#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20483#[cfg_attr(feature = "ts", derive(TS))]
20484#[cfg_attr(feature = "ts", ts(export))]
20485pub struct MANUAL_CONTROL_DATA {
20486 #[doc = "X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle."]
20487 pub x: i16,
20488 #[doc = "Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle."]
20489 pub y: i16,
20490 #[doc = "Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust."]
20491 pub z: i16,
20492 #[doc = "R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle."]
20493 pub r: i16,
20494 #[doc = "A bitfield corresponding to the joystick buttons' 0-15 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1."]
20495 pub buttons: u16,
20496 #[doc = "The system to be controlled."]
20497 pub target: u8,
20498 #[doc = "A bitfield corresponding to the joystick buttons' 16-31 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 16."]
20499 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20500 pub buttons2: u16,
20501 #[doc = "Set bits to 1 to indicate which of the following extension fields contain valid data: bit 0: pitch, bit 1: roll, bit 2: aux1, bit 3: aux2, bit 4: aux3, bit 5: aux4, bit 6: aux5, bit 7: aux6"]
20502 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20503 pub enabled_extensions: u8,
20504 #[doc = "Pitch-only-axis, normalized to the range [-1000,1000]. Generally corresponds to pitch on vehicles with additional degrees of freedom. Valid if bit 0 of enabled_extensions field is set. Set to 0 if invalid."]
20505 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20506 pub s: i16,
20507 #[doc = "Roll-only-axis, normalized to the range [-1000,1000]. Generally corresponds to roll on vehicles with additional degrees of freedom. Valid if bit 1 of enabled_extensions field is set. Set to 0 if invalid."]
20508 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20509 pub t: i16,
20510 #[doc = "Aux continuous input field 1. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 2 of enabled_extensions field is set. 0 if bit 2 is unset."]
20511 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20512 pub aux1: i16,
20513 #[doc = "Aux continuous input field 2. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 3 of enabled_extensions field is set. 0 if bit 3 is unset."]
20514 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20515 pub aux2: i16,
20516 #[doc = "Aux continuous input field 3. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 4 of enabled_extensions field is set. 0 if bit 4 is unset."]
20517 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20518 pub aux3: i16,
20519 #[doc = "Aux continuous input field 4. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 5 of enabled_extensions field is set. 0 if bit 5 is unset."]
20520 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20521 pub aux4: i16,
20522 #[doc = "Aux continuous input field 5. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 6 of enabled_extensions field is set. 0 if bit 6 is unset."]
20523 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20524 pub aux5: i16,
20525 #[doc = "Aux continuous input field 6. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 7 of enabled_extensions field is set. 0 if bit 7 is unset."]
20526 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20527 pub aux6: i16,
20528}
20529impl MANUAL_CONTROL_DATA {
20530 pub const ENCODED_LEN: usize = 30usize;
20531 pub const DEFAULT: Self = Self {
20532 x: 0_i16,
20533 y: 0_i16,
20534 z: 0_i16,
20535 r: 0_i16,
20536 buttons: 0_u16,
20537 target: 0_u8,
20538 buttons2: 0_u16,
20539 enabled_extensions: 0_u8,
20540 s: 0_i16,
20541 t: 0_i16,
20542 aux1: 0_i16,
20543 aux2: 0_i16,
20544 aux3: 0_i16,
20545 aux4: 0_i16,
20546 aux5: 0_i16,
20547 aux6: 0_i16,
20548 };
20549 #[cfg(feature = "arbitrary")]
20550 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20551 use arbitrary::{Arbitrary, Unstructured};
20552 let mut buf = [0u8; 1024];
20553 rng.fill_bytes(&mut buf);
20554 let mut unstructured = Unstructured::new(&buf);
20555 Self::arbitrary(&mut unstructured).unwrap_or_default()
20556 }
20557}
20558impl Default for MANUAL_CONTROL_DATA {
20559 fn default() -> Self {
20560 Self::DEFAULT.clone()
20561 }
20562}
20563impl MessageData for MANUAL_CONTROL_DATA {
20564 type Message = MavMessage;
20565 const ID: u32 = 69u32;
20566 const NAME: &'static str = "MANUAL_CONTROL";
20567 const EXTRA_CRC: u8 = 243u8;
20568 const ENCODED_LEN: usize = 30usize;
20569 fn deser(
20570 _version: MavlinkVersion,
20571 __input: &[u8],
20572 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20573 let avail_len = __input.len();
20574 let mut payload_buf = [0; Self::ENCODED_LEN];
20575 let mut buf = if avail_len < Self::ENCODED_LEN {
20576 payload_buf[0..avail_len].copy_from_slice(__input);
20577 Bytes::new(&payload_buf)
20578 } else {
20579 Bytes::new(__input)
20580 };
20581 let mut __struct = Self::default();
20582 __struct.x = buf.get_i16_le()?;
20583 __struct.y = buf.get_i16_le()?;
20584 __struct.z = buf.get_i16_le()?;
20585 __struct.r = buf.get_i16_le()?;
20586 __struct.buttons = buf.get_u16_le()?;
20587 __struct.target = buf.get_u8()?;
20588 __struct.buttons2 = buf.get_u16_le()?;
20589 __struct.enabled_extensions = buf.get_u8()?;
20590 __struct.s = buf.get_i16_le()?;
20591 __struct.t = buf.get_i16_le()?;
20592 __struct.aux1 = buf.get_i16_le()?;
20593 __struct.aux2 = buf.get_i16_le()?;
20594 __struct.aux3 = buf.get_i16_le()?;
20595 __struct.aux4 = buf.get_i16_le()?;
20596 __struct.aux5 = buf.get_i16_le()?;
20597 __struct.aux6 = buf.get_i16_le()?;
20598 Ok(__struct)
20599 }
20600 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20601 let mut __tmp = BytesMut::new(bytes);
20602 #[allow(clippy::absurd_extreme_comparisons)]
20603 #[allow(unused_comparisons)]
20604 if __tmp.remaining() < Self::ENCODED_LEN {
20605 panic!(
20606 "buffer is too small (need {} bytes, but got {})",
20607 Self::ENCODED_LEN,
20608 __tmp.remaining(),
20609 )
20610 }
20611 __tmp.put_i16_le(self.x);
20612 __tmp.put_i16_le(self.y);
20613 __tmp.put_i16_le(self.z);
20614 __tmp.put_i16_le(self.r);
20615 __tmp.put_u16_le(self.buttons);
20616 __tmp.put_u8(self.target);
20617 if matches!(version, MavlinkVersion::V2) {
20618 __tmp.put_u16_le(self.buttons2);
20619 __tmp.put_u8(self.enabled_extensions);
20620 __tmp.put_i16_le(self.s);
20621 __tmp.put_i16_le(self.t);
20622 __tmp.put_i16_le(self.aux1);
20623 __tmp.put_i16_le(self.aux2);
20624 __tmp.put_i16_le(self.aux3);
20625 __tmp.put_i16_le(self.aux4);
20626 __tmp.put_i16_le(self.aux5);
20627 __tmp.put_i16_le(self.aux6);
20628 let len = __tmp.len();
20629 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20630 } else {
20631 __tmp.len()
20632 }
20633 }
20634}
20635#[doc = "Setpoint in roll, pitch, yaw and thrust from the operator."]
20636#[doc = ""]
20637#[doc = "ID: 81"]
20638#[derive(Debug, Clone, PartialEq)]
20639#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20640#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20641#[cfg_attr(feature = "ts", derive(TS))]
20642#[cfg_attr(feature = "ts", ts(export))]
20643pub struct MANUAL_SETPOINT_DATA {
20644 #[doc = "Timestamp (time since system boot)."]
20645 pub time_boot_ms: u32,
20646 #[doc = "Desired roll rate"]
20647 pub roll: f32,
20648 #[doc = "Desired pitch rate"]
20649 pub pitch: f32,
20650 #[doc = "Desired yaw rate"]
20651 pub yaw: f32,
20652 #[doc = "Collective thrust, normalized to 0 .. 1"]
20653 pub thrust: f32,
20654 #[doc = "Flight mode switch position, 0.. 255"]
20655 pub mode_switch: u8,
20656 #[doc = "Override mode switch position, 0.. 255"]
20657 pub manual_override_switch: u8,
20658}
20659impl MANUAL_SETPOINT_DATA {
20660 pub const ENCODED_LEN: usize = 22usize;
20661 pub const DEFAULT: Self = Self {
20662 time_boot_ms: 0_u32,
20663 roll: 0.0_f32,
20664 pitch: 0.0_f32,
20665 yaw: 0.0_f32,
20666 thrust: 0.0_f32,
20667 mode_switch: 0_u8,
20668 manual_override_switch: 0_u8,
20669 };
20670 #[cfg(feature = "arbitrary")]
20671 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20672 use arbitrary::{Arbitrary, Unstructured};
20673 let mut buf = [0u8; 1024];
20674 rng.fill_bytes(&mut buf);
20675 let mut unstructured = Unstructured::new(&buf);
20676 Self::arbitrary(&mut unstructured).unwrap_or_default()
20677 }
20678}
20679impl Default for MANUAL_SETPOINT_DATA {
20680 fn default() -> Self {
20681 Self::DEFAULT.clone()
20682 }
20683}
20684impl MessageData for MANUAL_SETPOINT_DATA {
20685 type Message = MavMessage;
20686 const ID: u32 = 81u32;
20687 const NAME: &'static str = "MANUAL_SETPOINT";
20688 const EXTRA_CRC: u8 = 106u8;
20689 const ENCODED_LEN: usize = 22usize;
20690 fn deser(
20691 _version: MavlinkVersion,
20692 __input: &[u8],
20693 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20694 let avail_len = __input.len();
20695 let mut payload_buf = [0; Self::ENCODED_LEN];
20696 let mut buf = if avail_len < Self::ENCODED_LEN {
20697 payload_buf[0..avail_len].copy_from_slice(__input);
20698 Bytes::new(&payload_buf)
20699 } else {
20700 Bytes::new(__input)
20701 };
20702 let mut __struct = Self::default();
20703 __struct.time_boot_ms = buf.get_u32_le()?;
20704 __struct.roll = buf.get_f32_le()?;
20705 __struct.pitch = buf.get_f32_le()?;
20706 __struct.yaw = buf.get_f32_le()?;
20707 __struct.thrust = buf.get_f32_le()?;
20708 __struct.mode_switch = buf.get_u8()?;
20709 __struct.manual_override_switch = buf.get_u8()?;
20710 Ok(__struct)
20711 }
20712 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20713 let mut __tmp = BytesMut::new(bytes);
20714 #[allow(clippy::absurd_extreme_comparisons)]
20715 #[allow(unused_comparisons)]
20716 if __tmp.remaining() < Self::ENCODED_LEN {
20717 panic!(
20718 "buffer is too small (need {} bytes, but got {})",
20719 Self::ENCODED_LEN,
20720 __tmp.remaining(),
20721 )
20722 }
20723 __tmp.put_u32_le(self.time_boot_ms);
20724 __tmp.put_f32_le(self.roll);
20725 __tmp.put_f32_le(self.pitch);
20726 __tmp.put_f32_le(self.yaw);
20727 __tmp.put_f32_le(self.thrust);
20728 __tmp.put_u8(self.mode_switch);
20729 __tmp.put_u8(self.manual_override_switch);
20730 if matches!(version, MavlinkVersion::V2) {
20731 let len = __tmp.len();
20732 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20733 } else {
20734 __tmp.len()
20735 }
20736 }
20737}
20738#[doc = "Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output."]
20739#[doc = ""]
20740#[doc = "ID: 249"]
20741#[derive(Debug, Clone, PartialEq)]
20742#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20743#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20744#[cfg_attr(feature = "ts", derive(TS))]
20745#[cfg_attr(feature = "ts", ts(export))]
20746pub struct MEMORY_VECT_DATA {
20747 #[doc = "Starting address of the debug variables"]
20748 pub address: u16,
20749 #[doc = "Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below"]
20750 pub ver: u8,
20751 #[doc = "Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14"]
20752 pub mavtype: u8,
20753 #[doc = "Memory contents at specified address"]
20754 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20755 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
20756 pub value: [i8; 32],
20757}
20758impl MEMORY_VECT_DATA {
20759 pub const ENCODED_LEN: usize = 36usize;
20760 pub const DEFAULT: Self = Self {
20761 address: 0_u16,
20762 ver: 0_u8,
20763 mavtype: 0_u8,
20764 value: [0_i8; 32usize],
20765 };
20766 #[cfg(feature = "arbitrary")]
20767 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20768 use arbitrary::{Arbitrary, Unstructured};
20769 let mut buf = [0u8; 1024];
20770 rng.fill_bytes(&mut buf);
20771 let mut unstructured = Unstructured::new(&buf);
20772 Self::arbitrary(&mut unstructured).unwrap_or_default()
20773 }
20774}
20775impl Default for MEMORY_VECT_DATA {
20776 fn default() -> Self {
20777 Self::DEFAULT.clone()
20778 }
20779}
20780impl MessageData for MEMORY_VECT_DATA {
20781 type Message = MavMessage;
20782 const ID: u32 = 249u32;
20783 const NAME: &'static str = "MEMORY_VECT";
20784 const EXTRA_CRC: u8 = 204u8;
20785 const ENCODED_LEN: usize = 36usize;
20786 fn deser(
20787 _version: MavlinkVersion,
20788 __input: &[u8],
20789 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20790 let avail_len = __input.len();
20791 let mut payload_buf = [0; Self::ENCODED_LEN];
20792 let mut buf = if avail_len < Self::ENCODED_LEN {
20793 payload_buf[0..avail_len].copy_from_slice(__input);
20794 Bytes::new(&payload_buf)
20795 } else {
20796 Bytes::new(__input)
20797 };
20798 let mut __struct = Self::default();
20799 __struct.address = buf.get_u16_le()?;
20800 __struct.ver = buf.get_u8()?;
20801 __struct.mavtype = buf.get_u8()?;
20802 for v in &mut __struct.value {
20803 let val = buf.get_i8()?;
20804 *v = val;
20805 }
20806 Ok(__struct)
20807 }
20808 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20809 let mut __tmp = BytesMut::new(bytes);
20810 #[allow(clippy::absurd_extreme_comparisons)]
20811 #[allow(unused_comparisons)]
20812 if __tmp.remaining() < Self::ENCODED_LEN {
20813 panic!(
20814 "buffer is too small (need {} bytes, but got {})",
20815 Self::ENCODED_LEN,
20816 __tmp.remaining(),
20817 )
20818 }
20819 __tmp.put_u16_le(self.address);
20820 __tmp.put_u8(self.ver);
20821 __tmp.put_u8(self.mavtype);
20822 for val in &self.value {
20823 __tmp.put_i8(*val);
20824 }
20825 if matches!(version, MavlinkVersion::V2) {
20826 let len = __tmp.len();
20827 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20828 } else {
20829 __tmp.len()
20830 }
20831 }
20832}
20833#[doc = "The interval between messages for a particular MAVLink message ID. This message is sent in response to the MAV_CMD_REQUEST_MESSAGE command with param1=244 (this message) and param2=message_id (the id of the message for which the interval is required). \tIt may also be sent in response to MAV_CMD_GET_MESSAGE_INTERVAL. \tThis interface replaces DATA_STREAM."]
20834#[doc = ""]
20835#[doc = "ID: 244"]
20836#[derive(Debug, Clone, PartialEq)]
20837#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20838#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20839#[cfg_attr(feature = "ts", derive(TS))]
20840#[cfg_attr(feature = "ts", ts(export))]
20841pub struct MESSAGE_INTERVAL_DATA {
20842 #[doc = "The interval between two messages. A value of -1 indicates this stream is disabled, 0 indicates it is not available,>0 indicates the interval at which it is sent."]
20843 pub interval_us: i32,
20844 #[doc = "The ID of the requested MAVLink message. v1.0 is limited to 254 messages."]
20845 pub message_id: u16,
20846}
20847impl MESSAGE_INTERVAL_DATA {
20848 pub const ENCODED_LEN: usize = 6usize;
20849 pub const DEFAULT: Self = Self {
20850 interval_us: 0_i32,
20851 message_id: 0_u16,
20852 };
20853 #[cfg(feature = "arbitrary")]
20854 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20855 use arbitrary::{Arbitrary, Unstructured};
20856 let mut buf = [0u8; 1024];
20857 rng.fill_bytes(&mut buf);
20858 let mut unstructured = Unstructured::new(&buf);
20859 Self::arbitrary(&mut unstructured).unwrap_or_default()
20860 }
20861}
20862impl Default for MESSAGE_INTERVAL_DATA {
20863 fn default() -> Self {
20864 Self::DEFAULT.clone()
20865 }
20866}
20867impl MessageData for MESSAGE_INTERVAL_DATA {
20868 type Message = MavMessage;
20869 const ID: u32 = 244u32;
20870 const NAME: &'static str = "MESSAGE_INTERVAL";
20871 const EXTRA_CRC: u8 = 95u8;
20872 const ENCODED_LEN: usize = 6usize;
20873 fn deser(
20874 _version: MavlinkVersion,
20875 __input: &[u8],
20876 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20877 let avail_len = __input.len();
20878 let mut payload_buf = [0; Self::ENCODED_LEN];
20879 let mut buf = if avail_len < Self::ENCODED_LEN {
20880 payload_buf[0..avail_len].copy_from_slice(__input);
20881 Bytes::new(&payload_buf)
20882 } else {
20883 Bytes::new(__input)
20884 };
20885 let mut __struct = Self::default();
20886 __struct.interval_us = buf.get_i32_le()?;
20887 __struct.message_id = buf.get_u16_le()?;
20888 Ok(__struct)
20889 }
20890 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20891 let mut __tmp = BytesMut::new(bytes);
20892 #[allow(clippy::absurd_extreme_comparisons)]
20893 #[allow(unused_comparisons)]
20894 if __tmp.remaining() < Self::ENCODED_LEN {
20895 panic!(
20896 "buffer is too small (need {} bytes, but got {})",
20897 Self::ENCODED_LEN,
20898 __tmp.remaining(),
20899 )
20900 }
20901 __tmp.put_i32_le(self.interval_us);
20902 __tmp.put_u16_le(self.message_id);
20903 if matches!(version, MavlinkVersion::V2) {
20904 let len = __tmp.len();
20905 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20906 } else {
20907 __tmp.len()
20908 }
20909 }
20910}
20911#[doc = "Acknowledgment message during waypoint handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero)."]
20912#[doc = ""]
20913#[doc = "ID: 47"]
20914#[derive(Debug, Clone, PartialEq)]
20915#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20916#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20917#[cfg_attr(feature = "ts", derive(TS))]
20918#[cfg_attr(feature = "ts", ts(export))]
20919pub struct MISSION_ACK_DATA {
20920 #[doc = "System ID"]
20921 pub target_system: u8,
20922 #[doc = "Component ID"]
20923 pub target_component: u8,
20924 #[doc = "Mission result."]
20925 pub mavtype: MavMissionResult,
20926 #[doc = "Mission type."]
20927 #[cfg_attr(feature = "serde", serde(default))]
20928 pub mission_type: MavMissionType,
20929 #[doc = "Id of new on-vehicle mission, fence, or rally point plan (on upload to vehicle). The id is calculated and returned by a vehicle when a new plan is uploaded by a GCS. The only requirement on the id is that it must change when there is any change to the on-vehicle plan type (there is no requirement that the id be globally unique). 0 on download from the vehicle to the GCS (on download the ID is set in MISSION_COUNT). 0 if plan ids are not supported. The current on-vehicle plan ids are streamed in `MISSION_CURRENT`, allowing a GCS to determine if any part of the plan has changed and needs to be re-uploaded."]
20930 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20931 pub opaque_id: u32,
20932}
20933impl MISSION_ACK_DATA {
20934 pub const ENCODED_LEN: usize = 8usize;
20935 pub const DEFAULT: Self = Self {
20936 target_system: 0_u8,
20937 target_component: 0_u8,
20938 mavtype: MavMissionResult::DEFAULT,
20939 mission_type: MavMissionType::DEFAULT,
20940 opaque_id: 0_u32,
20941 };
20942 #[cfg(feature = "arbitrary")]
20943 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20944 use arbitrary::{Arbitrary, Unstructured};
20945 let mut buf = [0u8; 1024];
20946 rng.fill_bytes(&mut buf);
20947 let mut unstructured = Unstructured::new(&buf);
20948 Self::arbitrary(&mut unstructured).unwrap_or_default()
20949 }
20950}
20951impl Default for MISSION_ACK_DATA {
20952 fn default() -> Self {
20953 Self::DEFAULT.clone()
20954 }
20955}
20956impl MessageData for MISSION_ACK_DATA {
20957 type Message = MavMessage;
20958 const ID: u32 = 47u32;
20959 const NAME: &'static str = "MISSION_ACK";
20960 const EXTRA_CRC: u8 = 153u8;
20961 const ENCODED_LEN: usize = 8usize;
20962 fn deser(
20963 _version: MavlinkVersion,
20964 __input: &[u8],
20965 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20966 let avail_len = __input.len();
20967 let mut payload_buf = [0; Self::ENCODED_LEN];
20968 let mut buf = if avail_len < Self::ENCODED_LEN {
20969 payload_buf[0..avail_len].copy_from_slice(__input);
20970 Bytes::new(&payload_buf)
20971 } else {
20972 Bytes::new(__input)
20973 };
20974 let mut __struct = Self::default();
20975 __struct.target_system = buf.get_u8()?;
20976 __struct.target_component = buf.get_u8()?;
20977 let tmp = buf.get_u8()?;
20978 __struct.mavtype =
20979 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
20980 enum_type: "MavMissionResult",
20981 value: tmp as u64,
20982 })?;
20983 let tmp = buf.get_u8()?;
20984 __struct.mission_type =
20985 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
20986 enum_type: "MavMissionType",
20987 value: tmp as u64,
20988 })?;
20989 __struct.opaque_id = buf.get_u32_le()?;
20990 Ok(__struct)
20991 }
20992 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20993 let mut __tmp = BytesMut::new(bytes);
20994 #[allow(clippy::absurd_extreme_comparisons)]
20995 #[allow(unused_comparisons)]
20996 if __tmp.remaining() < Self::ENCODED_LEN {
20997 panic!(
20998 "buffer is too small (need {} bytes, but got {})",
20999 Self::ENCODED_LEN,
21000 __tmp.remaining(),
21001 )
21002 }
21003 __tmp.put_u8(self.target_system);
21004 __tmp.put_u8(self.target_component);
21005 __tmp.put_u8(self.mavtype as u8);
21006 if matches!(version, MavlinkVersion::V2) {
21007 __tmp.put_u8(self.mission_type as u8);
21008 __tmp.put_u32_le(self.opaque_id);
21009 let len = __tmp.len();
21010 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21011 } else {
21012 __tmp.len()
21013 }
21014 }
21015}
21016#[doc = "Delete all mission items at once."]
21017#[doc = ""]
21018#[doc = "ID: 45"]
21019#[derive(Debug, Clone, PartialEq)]
21020#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21021#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21022#[cfg_attr(feature = "ts", derive(TS))]
21023#[cfg_attr(feature = "ts", ts(export))]
21024pub struct MISSION_CLEAR_ALL_DATA {
21025 #[doc = "System ID"]
21026 pub target_system: u8,
21027 #[doc = "Component ID"]
21028 pub target_component: u8,
21029 #[doc = "Mission type."]
21030 #[cfg_attr(feature = "serde", serde(default))]
21031 pub mission_type: MavMissionType,
21032}
21033impl MISSION_CLEAR_ALL_DATA {
21034 pub const ENCODED_LEN: usize = 3usize;
21035 pub const DEFAULT: Self = Self {
21036 target_system: 0_u8,
21037 target_component: 0_u8,
21038 mission_type: MavMissionType::DEFAULT,
21039 };
21040 #[cfg(feature = "arbitrary")]
21041 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21042 use arbitrary::{Arbitrary, Unstructured};
21043 let mut buf = [0u8; 1024];
21044 rng.fill_bytes(&mut buf);
21045 let mut unstructured = Unstructured::new(&buf);
21046 Self::arbitrary(&mut unstructured).unwrap_or_default()
21047 }
21048}
21049impl Default for MISSION_CLEAR_ALL_DATA {
21050 fn default() -> Self {
21051 Self::DEFAULT.clone()
21052 }
21053}
21054impl MessageData for MISSION_CLEAR_ALL_DATA {
21055 type Message = MavMessage;
21056 const ID: u32 = 45u32;
21057 const NAME: &'static str = "MISSION_CLEAR_ALL";
21058 const EXTRA_CRC: u8 = 232u8;
21059 const ENCODED_LEN: usize = 3usize;
21060 fn deser(
21061 _version: MavlinkVersion,
21062 __input: &[u8],
21063 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21064 let avail_len = __input.len();
21065 let mut payload_buf = [0; Self::ENCODED_LEN];
21066 let mut buf = if avail_len < Self::ENCODED_LEN {
21067 payload_buf[0..avail_len].copy_from_slice(__input);
21068 Bytes::new(&payload_buf)
21069 } else {
21070 Bytes::new(__input)
21071 };
21072 let mut __struct = Self::default();
21073 __struct.target_system = buf.get_u8()?;
21074 __struct.target_component = buf.get_u8()?;
21075 let tmp = buf.get_u8()?;
21076 __struct.mission_type =
21077 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21078 enum_type: "MavMissionType",
21079 value: tmp as u64,
21080 })?;
21081 Ok(__struct)
21082 }
21083 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21084 let mut __tmp = BytesMut::new(bytes);
21085 #[allow(clippy::absurd_extreme_comparisons)]
21086 #[allow(unused_comparisons)]
21087 if __tmp.remaining() < Self::ENCODED_LEN {
21088 panic!(
21089 "buffer is too small (need {} bytes, but got {})",
21090 Self::ENCODED_LEN,
21091 __tmp.remaining(),
21092 )
21093 }
21094 __tmp.put_u8(self.target_system);
21095 __tmp.put_u8(self.target_component);
21096 if matches!(version, MavlinkVersion::V2) {
21097 __tmp.put_u8(self.mission_type as u8);
21098 let len = __tmp.len();
21099 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21100 } else {
21101 __tmp.len()
21102 }
21103 }
21104}
21105#[doc = "This message is emitted as response to MISSION_REQUEST_LIST by the MAV and to initiate a write transaction. The GCS can then request the individual mission item based on the knowledge of the total number of waypoints."]
21106#[doc = ""]
21107#[doc = "ID: 44"]
21108#[derive(Debug, Clone, PartialEq)]
21109#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21110#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21111#[cfg_attr(feature = "ts", derive(TS))]
21112#[cfg_attr(feature = "ts", ts(export))]
21113pub struct MISSION_COUNT_DATA {
21114 #[doc = "Number of mission items in the sequence"]
21115 pub count: u16,
21116 #[doc = "System ID"]
21117 pub target_system: u8,
21118 #[doc = "Component ID"]
21119 pub target_component: u8,
21120 #[doc = "Mission type."]
21121 #[cfg_attr(feature = "serde", serde(default))]
21122 pub mission_type: MavMissionType,
21123 #[doc = "Id of current on-vehicle mission, fence, or rally point plan (on download from vehicle). This field is used when downloading a plan from a vehicle to a GCS. 0 on upload to the vehicle from GCS. 0 if plan ids are not supported. The current on-vehicle plan ids are streamed in `MISSION_CURRENT`, allowing a GCS to determine if any part of the plan has changed and needs to be re-uploaded. The ids are recalculated by the vehicle when any part of the on-vehicle plan changes (when a new plan is uploaded, the vehicle returns the new id to the GCS in MISSION_ACK)."]
21124 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21125 pub opaque_id: u32,
21126}
21127impl MISSION_COUNT_DATA {
21128 pub const ENCODED_LEN: usize = 9usize;
21129 pub const DEFAULT: Self = Self {
21130 count: 0_u16,
21131 target_system: 0_u8,
21132 target_component: 0_u8,
21133 mission_type: MavMissionType::DEFAULT,
21134 opaque_id: 0_u32,
21135 };
21136 #[cfg(feature = "arbitrary")]
21137 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21138 use arbitrary::{Arbitrary, Unstructured};
21139 let mut buf = [0u8; 1024];
21140 rng.fill_bytes(&mut buf);
21141 let mut unstructured = Unstructured::new(&buf);
21142 Self::arbitrary(&mut unstructured).unwrap_or_default()
21143 }
21144}
21145impl Default for MISSION_COUNT_DATA {
21146 fn default() -> Self {
21147 Self::DEFAULT.clone()
21148 }
21149}
21150impl MessageData for MISSION_COUNT_DATA {
21151 type Message = MavMessage;
21152 const ID: u32 = 44u32;
21153 const NAME: &'static str = "MISSION_COUNT";
21154 const EXTRA_CRC: u8 = 221u8;
21155 const ENCODED_LEN: usize = 9usize;
21156 fn deser(
21157 _version: MavlinkVersion,
21158 __input: &[u8],
21159 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21160 let avail_len = __input.len();
21161 let mut payload_buf = [0; Self::ENCODED_LEN];
21162 let mut buf = if avail_len < Self::ENCODED_LEN {
21163 payload_buf[0..avail_len].copy_from_slice(__input);
21164 Bytes::new(&payload_buf)
21165 } else {
21166 Bytes::new(__input)
21167 };
21168 let mut __struct = Self::default();
21169 __struct.count = buf.get_u16_le()?;
21170 __struct.target_system = buf.get_u8()?;
21171 __struct.target_component = buf.get_u8()?;
21172 let tmp = buf.get_u8()?;
21173 __struct.mission_type =
21174 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21175 enum_type: "MavMissionType",
21176 value: tmp as u64,
21177 })?;
21178 __struct.opaque_id = buf.get_u32_le()?;
21179 Ok(__struct)
21180 }
21181 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21182 let mut __tmp = BytesMut::new(bytes);
21183 #[allow(clippy::absurd_extreme_comparisons)]
21184 #[allow(unused_comparisons)]
21185 if __tmp.remaining() < Self::ENCODED_LEN {
21186 panic!(
21187 "buffer is too small (need {} bytes, but got {})",
21188 Self::ENCODED_LEN,
21189 __tmp.remaining(),
21190 )
21191 }
21192 __tmp.put_u16_le(self.count);
21193 __tmp.put_u8(self.target_system);
21194 __tmp.put_u8(self.target_component);
21195 if matches!(version, MavlinkVersion::V2) {
21196 __tmp.put_u8(self.mission_type as u8);
21197 __tmp.put_u32_le(self.opaque_id);
21198 let len = __tmp.len();
21199 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21200 } else {
21201 __tmp.len()
21202 }
21203 }
21204}
21205#[doc = "Message that announces the sequence number of the current target mission item (that the system will fly towards/execute when the mission is running). This message should be streamed all the time (nominally at 1Hz). This message should be emitted following a call to MAV_CMD_DO_SET_MISSION_CURRENT or MISSION_SET_CURRENT."]
21206#[doc = ""]
21207#[doc = "ID: 42"]
21208#[derive(Debug, Clone, PartialEq)]
21209#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21210#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21211#[cfg_attr(feature = "ts", derive(TS))]
21212#[cfg_attr(feature = "ts", ts(export))]
21213pub struct MISSION_CURRENT_DATA {
21214 #[doc = "Sequence"]
21215 pub seq: u16,
21216 #[doc = "Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle."]
21217 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21218 pub total: u16,
21219 #[doc = "Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported."]
21220 #[cfg_attr(feature = "serde", serde(default))]
21221 pub mission_state: MissionState,
21222 #[doc = "Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode)."]
21223 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21224 pub mission_mode: u8,
21225 #[doc = "Id of current on-vehicle mission plan, or 0 if IDs are not supported or there is no mission loaded. GCS can use this to track changes to the mission plan type. The same value is returned on mission upload (in the MISSION_ACK)."]
21226 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21227 pub mission_id: u32,
21228 #[doc = "Id of current on-vehicle fence plan, or 0 if IDs are not supported or there is no fence loaded. GCS can use this to track changes to the fence plan type. The same value is returned on fence upload (in the MISSION_ACK)."]
21229 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21230 pub fence_id: u32,
21231 #[doc = "Id of current on-vehicle rally point plan, or 0 if IDs are not supported or there are no rally points loaded. GCS can use this to track changes to the rally point plan type. The same value is returned on rally point upload (in the MISSION_ACK)."]
21232 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21233 pub rally_points_id: u32,
21234}
21235impl MISSION_CURRENT_DATA {
21236 pub const ENCODED_LEN: usize = 18usize;
21237 pub const DEFAULT: Self = Self {
21238 seq: 0_u16,
21239 total: 0_u16,
21240 mission_state: MissionState::DEFAULT,
21241 mission_mode: 0_u8,
21242 mission_id: 0_u32,
21243 fence_id: 0_u32,
21244 rally_points_id: 0_u32,
21245 };
21246 #[cfg(feature = "arbitrary")]
21247 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21248 use arbitrary::{Arbitrary, Unstructured};
21249 let mut buf = [0u8; 1024];
21250 rng.fill_bytes(&mut buf);
21251 let mut unstructured = Unstructured::new(&buf);
21252 Self::arbitrary(&mut unstructured).unwrap_or_default()
21253 }
21254}
21255impl Default for MISSION_CURRENT_DATA {
21256 fn default() -> Self {
21257 Self::DEFAULT.clone()
21258 }
21259}
21260impl MessageData for MISSION_CURRENT_DATA {
21261 type Message = MavMessage;
21262 const ID: u32 = 42u32;
21263 const NAME: &'static str = "MISSION_CURRENT";
21264 const EXTRA_CRC: u8 = 28u8;
21265 const ENCODED_LEN: usize = 18usize;
21266 fn deser(
21267 _version: MavlinkVersion,
21268 __input: &[u8],
21269 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21270 let avail_len = __input.len();
21271 let mut payload_buf = [0; Self::ENCODED_LEN];
21272 let mut buf = if avail_len < Self::ENCODED_LEN {
21273 payload_buf[0..avail_len].copy_from_slice(__input);
21274 Bytes::new(&payload_buf)
21275 } else {
21276 Bytes::new(__input)
21277 };
21278 let mut __struct = Self::default();
21279 __struct.seq = buf.get_u16_le()?;
21280 __struct.total = buf.get_u16_le()?;
21281 let tmp = buf.get_u8()?;
21282 __struct.mission_state =
21283 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21284 enum_type: "MissionState",
21285 value: tmp as u64,
21286 })?;
21287 __struct.mission_mode = buf.get_u8()?;
21288 __struct.mission_id = buf.get_u32_le()?;
21289 __struct.fence_id = buf.get_u32_le()?;
21290 __struct.rally_points_id = buf.get_u32_le()?;
21291 Ok(__struct)
21292 }
21293 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21294 let mut __tmp = BytesMut::new(bytes);
21295 #[allow(clippy::absurd_extreme_comparisons)]
21296 #[allow(unused_comparisons)]
21297 if __tmp.remaining() < Self::ENCODED_LEN {
21298 panic!(
21299 "buffer is too small (need {} bytes, but got {})",
21300 Self::ENCODED_LEN,
21301 __tmp.remaining(),
21302 )
21303 }
21304 __tmp.put_u16_le(self.seq);
21305 if matches!(version, MavlinkVersion::V2) {
21306 __tmp.put_u16_le(self.total);
21307 __tmp.put_u8(self.mission_state as u8);
21308 __tmp.put_u8(self.mission_mode);
21309 __tmp.put_u32_le(self.mission_id);
21310 __tmp.put_u32_le(self.fence_id);
21311 __tmp.put_u32_le(self.rally_points_id);
21312 let len = __tmp.len();
21313 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21314 } else {
21315 __tmp.len()
21316 }
21317 }
21318}
21319#[deprecated = " See `MISSION_ITEM_INT` (Deprecated since 2020-06)"]
21320#[doc = "Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN may be used to indicate an optional/default value (e.g. to use the system's current latitude or yaw rather than a specific value). See also <https://mavlink.io/en/services/mission.html>."]
21321#[doc = ""]
21322#[doc = "ID: 39"]
21323#[derive(Debug, Clone, PartialEq)]
21324#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21325#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21326#[cfg_attr(feature = "ts", derive(TS))]
21327#[cfg_attr(feature = "ts", ts(export))]
21328pub struct MISSION_ITEM_DATA {
21329 #[doc = "PARAM1, see MAV_CMD enum"]
21330 pub param1: f32,
21331 #[doc = "PARAM2, see MAV_CMD enum"]
21332 pub param2: f32,
21333 #[doc = "PARAM3, see MAV_CMD enum"]
21334 pub param3: f32,
21335 #[doc = "PARAM4, see MAV_CMD enum"]
21336 pub param4: f32,
21337 #[doc = "PARAM5 / local: X coordinate, global: latitude"]
21338 pub x: f32,
21339 #[doc = "PARAM6 / local: Y coordinate, global: longitude"]
21340 pub y: f32,
21341 #[doc = "PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame)."]
21342 pub z: f32,
21343 #[doc = "Sequence"]
21344 pub seq: u16,
21345 #[doc = "The scheduled action for the waypoint."]
21346 pub command: MavCmd,
21347 #[doc = "System ID"]
21348 pub target_system: u8,
21349 #[doc = "Component ID"]
21350 pub target_component: u8,
21351 #[doc = "The coordinate system of the waypoint."]
21352 pub frame: MavFrame,
21353 #[doc = "false:0, true:1"]
21354 pub current: u8,
21355 #[doc = "Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes."]
21356 pub autocontinue: u8,
21357 #[doc = "Mission type."]
21358 #[cfg_attr(feature = "serde", serde(default))]
21359 pub mission_type: MavMissionType,
21360}
21361impl MISSION_ITEM_DATA {
21362 pub const ENCODED_LEN: usize = 38usize;
21363 pub const DEFAULT: Self = Self {
21364 param1: 0.0_f32,
21365 param2: 0.0_f32,
21366 param3: 0.0_f32,
21367 param4: 0.0_f32,
21368 x: 0.0_f32,
21369 y: 0.0_f32,
21370 z: 0.0_f32,
21371 seq: 0_u16,
21372 command: MavCmd::DEFAULT,
21373 target_system: 0_u8,
21374 target_component: 0_u8,
21375 frame: MavFrame::DEFAULT,
21376 current: 0_u8,
21377 autocontinue: 0_u8,
21378 mission_type: MavMissionType::DEFAULT,
21379 };
21380 #[cfg(feature = "arbitrary")]
21381 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21382 use arbitrary::{Arbitrary, Unstructured};
21383 let mut buf = [0u8; 1024];
21384 rng.fill_bytes(&mut buf);
21385 let mut unstructured = Unstructured::new(&buf);
21386 Self::arbitrary(&mut unstructured).unwrap_or_default()
21387 }
21388}
21389impl Default for MISSION_ITEM_DATA {
21390 fn default() -> Self {
21391 Self::DEFAULT.clone()
21392 }
21393}
21394impl MessageData for MISSION_ITEM_DATA {
21395 type Message = MavMessage;
21396 const ID: u32 = 39u32;
21397 const NAME: &'static str = "MISSION_ITEM";
21398 const EXTRA_CRC: u8 = 254u8;
21399 const ENCODED_LEN: usize = 38usize;
21400 fn deser(
21401 _version: MavlinkVersion,
21402 __input: &[u8],
21403 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21404 let avail_len = __input.len();
21405 let mut payload_buf = [0; Self::ENCODED_LEN];
21406 let mut buf = if avail_len < Self::ENCODED_LEN {
21407 payload_buf[0..avail_len].copy_from_slice(__input);
21408 Bytes::new(&payload_buf)
21409 } else {
21410 Bytes::new(__input)
21411 };
21412 let mut __struct = Self::default();
21413 __struct.param1 = buf.get_f32_le()?;
21414 __struct.param2 = buf.get_f32_le()?;
21415 __struct.param3 = buf.get_f32_le()?;
21416 __struct.param4 = buf.get_f32_le()?;
21417 __struct.x = buf.get_f32_le()?;
21418 __struct.y = buf.get_f32_le()?;
21419 __struct.z = buf.get_f32_le()?;
21420 __struct.seq = buf.get_u16_le()?;
21421 let tmp = buf.get_u16_le()?;
21422 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
21423 ::mavlink_core::error::ParserError::InvalidEnum {
21424 enum_type: "MavCmd",
21425 value: tmp as u64,
21426 },
21427 )?;
21428 __struct.target_system = buf.get_u8()?;
21429 __struct.target_component = buf.get_u8()?;
21430 let tmp = buf.get_u8()?;
21431 __struct.frame =
21432 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21433 enum_type: "MavFrame",
21434 value: tmp as u64,
21435 })?;
21436 __struct.current = buf.get_u8()?;
21437 __struct.autocontinue = buf.get_u8()?;
21438 let tmp = buf.get_u8()?;
21439 __struct.mission_type =
21440 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21441 enum_type: "MavMissionType",
21442 value: tmp as u64,
21443 })?;
21444 Ok(__struct)
21445 }
21446 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21447 let mut __tmp = BytesMut::new(bytes);
21448 #[allow(clippy::absurd_extreme_comparisons)]
21449 #[allow(unused_comparisons)]
21450 if __tmp.remaining() < Self::ENCODED_LEN {
21451 panic!(
21452 "buffer is too small (need {} bytes, but got {})",
21453 Self::ENCODED_LEN,
21454 __tmp.remaining(),
21455 )
21456 }
21457 __tmp.put_f32_le(self.param1);
21458 __tmp.put_f32_le(self.param2);
21459 __tmp.put_f32_le(self.param3);
21460 __tmp.put_f32_le(self.param4);
21461 __tmp.put_f32_le(self.x);
21462 __tmp.put_f32_le(self.y);
21463 __tmp.put_f32_le(self.z);
21464 __tmp.put_u16_le(self.seq);
21465 __tmp.put_u16_le(self.command as u16);
21466 __tmp.put_u8(self.target_system);
21467 __tmp.put_u8(self.target_component);
21468 __tmp.put_u8(self.frame as u8);
21469 __tmp.put_u8(self.current);
21470 __tmp.put_u8(self.autocontinue);
21471 if matches!(version, MavlinkVersion::V2) {
21472 __tmp.put_u8(self.mission_type as u8);
21473 let len = __tmp.len();
21474 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21475 } else {
21476 __tmp.len()
21477 }
21478 }
21479}
21480#[doc = "Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). See also <https://mavlink.io/en/services/mission.html>."]
21481#[doc = ""]
21482#[doc = "ID: 73"]
21483#[derive(Debug, Clone, PartialEq)]
21484#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21485#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21486#[cfg_attr(feature = "ts", derive(TS))]
21487#[cfg_attr(feature = "ts", ts(export))]
21488pub struct MISSION_ITEM_INT_DATA {
21489 #[doc = "PARAM1, see MAV_CMD enum"]
21490 pub param1: f32,
21491 #[doc = "PARAM2, see MAV_CMD enum"]
21492 pub param2: f32,
21493 #[doc = "PARAM3, see MAV_CMD enum"]
21494 pub param3: f32,
21495 #[doc = "PARAM4, see MAV_CMD enum"]
21496 pub param4: f32,
21497 #[doc = "PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7"]
21498 pub x: i32,
21499 #[doc = "PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7"]
21500 pub y: i32,
21501 #[doc = "PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame."]
21502 pub z: f32,
21503 #[doc = "Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4)."]
21504 pub seq: u16,
21505 #[doc = "The scheduled action for the waypoint."]
21506 pub command: MavCmd,
21507 #[doc = "System ID"]
21508 pub target_system: u8,
21509 #[doc = "Component ID"]
21510 pub target_component: u8,
21511 #[doc = "The coordinate system of the waypoint."]
21512 pub frame: MavFrame,
21513 #[doc = "false:0, true:1"]
21514 pub current: u8,
21515 #[doc = "Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes."]
21516 pub autocontinue: u8,
21517 #[doc = "Mission type."]
21518 #[cfg_attr(feature = "serde", serde(default))]
21519 pub mission_type: MavMissionType,
21520}
21521impl MISSION_ITEM_INT_DATA {
21522 pub const ENCODED_LEN: usize = 38usize;
21523 pub const DEFAULT: Self = Self {
21524 param1: 0.0_f32,
21525 param2: 0.0_f32,
21526 param3: 0.0_f32,
21527 param4: 0.0_f32,
21528 x: 0_i32,
21529 y: 0_i32,
21530 z: 0.0_f32,
21531 seq: 0_u16,
21532 command: MavCmd::DEFAULT,
21533 target_system: 0_u8,
21534 target_component: 0_u8,
21535 frame: MavFrame::DEFAULT,
21536 current: 0_u8,
21537 autocontinue: 0_u8,
21538 mission_type: MavMissionType::DEFAULT,
21539 };
21540 #[cfg(feature = "arbitrary")]
21541 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21542 use arbitrary::{Arbitrary, Unstructured};
21543 let mut buf = [0u8; 1024];
21544 rng.fill_bytes(&mut buf);
21545 let mut unstructured = Unstructured::new(&buf);
21546 Self::arbitrary(&mut unstructured).unwrap_or_default()
21547 }
21548}
21549impl Default for MISSION_ITEM_INT_DATA {
21550 fn default() -> Self {
21551 Self::DEFAULT.clone()
21552 }
21553}
21554impl MessageData for MISSION_ITEM_INT_DATA {
21555 type Message = MavMessage;
21556 const ID: u32 = 73u32;
21557 const NAME: &'static str = "MISSION_ITEM_INT";
21558 const EXTRA_CRC: u8 = 38u8;
21559 const ENCODED_LEN: usize = 38usize;
21560 fn deser(
21561 _version: MavlinkVersion,
21562 __input: &[u8],
21563 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21564 let avail_len = __input.len();
21565 let mut payload_buf = [0; Self::ENCODED_LEN];
21566 let mut buf = if avail_len < Self::ENCODED_LEN {
21567 payload_buf[0..avail_len].copy_from_slice(__input);
21568 Bytes::new(&payload_buf)
21569 } else {
21570 Bytes::new(__input)
21571 };
21572 let mut __struct = Self::default();
21573 __struct.param1 = buf.get_f32_le()?;
21574 __struct.param2 = buf.get_f32_le()?;
21575 __struct.param3 = buf.get_f32_le()?;
21576 __struct.param4 = buf.get_f32_le()?;
21577 __struct.x = buf.get_i32_le()?;
21578 __struct.y = buf.get_i32_le()?;
21579 __struct.z = buf.get_f32_le()?;
21580 __struct.seq = buf.get_u16_le()?;
21581 let tmp = buf.get_u16_le()?;
21582 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
21583 ::mavlink_core::error::ParserError::InvalidEnum {
21584 enum_type: "MavCmd",
21585 value: tmp as u64,
21586 },
21587 )?;
21588 __struct.target_system = buf.get_u8()?;
21589 __struct.target_component = buf.get_u8()?;
21590 let tmp = buf.get_u8()?;
21591 __struct.frame =
21592 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21593 enum_type: "MavFrame",
21594 value: tmp as u64,
21595 })?;
21596 __struct.current = buf.get_u8()?;
21597 __struct.autocontinue = buf.get_u8()?;
21598 let tmp = buf.get_u8()?;
21599 __struct.mission_type =
21600 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21601 enum_type: "MavMissionType",
21602 value: tmp as u64,
21603 })?;
21604 Ok(__struct)
21605 }
21606 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21607 let mut __tmp = BytesMut::new(bytes);
21608 #[allow(clippy::absurd_extreme_comparisons)]
21609 #[allow(unused_comparisons)]
21610 if __tmp.remaining() < Self::ENCODED_LEN {
21611 panic!(
21612 "buffer is too small (need {} bytes, but got {})",
21613 Self::ENCODED_LEN,
21614 __tmp.remaining(),
21615 )
21616 }
21617 __tmp.put_f32_le(self.param1);
21618 __tmp.put_f32_le(self.param2);
21619 __tmp.put_f32_le(self.param3);
21620 __tmp.put_f32_le(self.param4);
21621 __tmp.put_i32_le(self.x);
21622 __tmp.put_i32_le(self.y);
21623 __tmp.put_f32_le(self.z);
21624 __tmp.put_u16_le(self.seq);
21625 __tmp.put_u16_le(self.command as u16);
21626 __tmp.put_u8(self.target_system);
21627 __tmp.put_u8(self.target_component);
21628 __tmp.put_u8(self.frame as u8);
21629 __tmp.put_u8(self.current);
21630 __tmp.put_u8(self.autocontinue);
21631 if matches!(version, MavlinkVersion::V2) {
21632 __tmp.put_u8(self.mission_type as u8);
21633 let len = __tmp.len();
21634 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21635 } else {
21636 __tmp.len()
21637 }
21638 }
21639}
21640#[doc = "A certain mission item has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next waypoint."]
21641#[doc = ""]
21642#[doc = "ID: 46"]
21643#[derive(Debug, Clone, PartialEq)]
21644#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21645#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21646#[cfg_attr(feature = "ts", derive(TS))]
21647#[cfg_attr(feature = "ts", ts(export))]
21648pub struct MISSION_ITEM_REACHED_DATA {
21649 #[doc = "Sequence"]
21650 pub seq: u16,
21651}
21652impl MISSION_ITEM_REACHED_DATA {
21653 pub const ENCODED_LEN: usize = 2usize;
21654 pub const DEFAULT: Self = Self { seq: 0_u16 };
21655 #[cfg(feature = "arbitrary")]
21656 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21657 use arbitrary::{Arbitrary, Unstructured};
21658 let mut buf = [0u8; 1024];
21659 rng.fill_bytes(&mut buf);
21660 let mut unstructured = Unstructured::new(&buf);
21661 Self::arbitrary(&mut unstructured).unwrap_or_default()
21662 }
21663}
21664impl Default for MISSION_ITEM_REACHED_DATA {
21665 fn default() -> Self {
21666 Self::DEFAULT.clone()
21667 }
21668}
21669impl MessageData for MISSION_ITEM_REACHED_DATA {
21670 type Message = MavMessage;
21671 const ID: u32 = 46u32;
21672 const NAME: &'static str = "MISSION_ITEM_REACHED";
21673 const EXTRA_CRC: u8 = 11u8;
21674 const ENCODED_LEN: usize = 2usize;
21675 fn deser(
21676 _version: MavlinkVersion,
21677 __input: &[u8],
21678 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21679 let avail_len = __input.len();
21680 let mut payload_buf = [0; Self::ENCODED_LEN];
21681 let mut buf = if avail_len < Self::ENCODED_LEN {
21682 payload_buf[0..avail_len].copy_from_slice(__input);
21683 Bytes::new(&payload_buf)
21684 } else {
21685 Bytes::new(__input)
21686 };
21687 let mut __struct = Self::default();
21688 __struct.seq = buf.get_u16_le()?;
21689 Ok(__struct)
21690 }
21691 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21692 let mut __tmp = BytesMut::new(bytes);
21693 #[allow(clippy::absurd_extreme_comparisons)]
21694 #[allow(unused_comparisons)]
21695 if __tmp.remaining() < Self::ENCODED_LEN {
21696 panic!(
21697 "buffer is too small (need {} bytes, but got {})",
21698 Self::ENCODED_LEN,
21699 __tmp.remaining(),
21700 )
21701 }
21702 __tmp.put_u16_le(self.seq);
21703 if matches!(version, MavlinkVersion::V2) {
21704 let len = __tmp.len();
21705 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21706 } else {
21707 __tmp.len()
21708 }
21709 }
21710}
21711#[deprecated = "A system that gets this request should respond with MISSION_ITEM_INT (as though MISSION_REQUEST_INT was received). See `MISSION_REQUEST_INT` (Deprecated since 2020-06)"]
21712#[doc = "Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. <https://mavlink.io/en/services/mission.html>."]
21713#[doc = ""]
21714#[doc = "ID: 40"]
21715#[derive(Debug, Clone, PartialEq)]
21716#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21717#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21718#[cfg_attr(feature = "ts", derive(TS))]
21719#[cfg_attr(feature = "ts", ts(export))]
21720pub struct MISSION_REQUEST_DATA {
21721 #[doc = "Sequence"]
21722 pub seq: u16,
21723 #[doc = "System ID"]
21724 pub target_system: u8,
21725 #[doc = "Component ID"]
21726 pub target_component: u8,
21727 #[doc = "Mission type."]
21728 #[cfg_attr(feature = "serde", serde(default))]
21729 pub mission_type: MavMissionType,
21730}
21731impl MISSION_REQUEST_DATA {
21732 pub const ENCODED_LEN: usize = 5usize;
21733 pub const DEFAULT: Self = Self {
21734 seq: 0_u16,
21735 target_system: 0_u8,
21736 target_component: 0_u8,
21737 mission_type: MavMissionType::DEFAULT,
21738 };
21739 #[cfg(feature = "arbitrary")]
21740 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21741 use arbitrary::{Arbitrary, Unstructured};
21742 let mut buf = [0u8; 1024];
21743 rng.fill_bytes(&mut buf);
21744 let mut unstructured = Unstructured::new(&buf);
21745 Self::arbitrary(&mut unstructured).unwrap_or_default()
21746 }
21747}
21748impl Default for MISSION_REQUEST_DATA {
21749 fn default() -> Self {
21750 Self::DEFAULT.clone()
21751 }
21752}
21753impl MessageData for MISSION_REQUEST_DATA {
21754 type Message = MavMessage;
21755 const ID: u32 = 40u32;
21756 const NAME: &'static str = "MISSION_REQUEST";
21757 const EXTRA_CRC: u8 = 230u8;
21758 const ENCODED_LEN: usize = 5usize;
21759 fn deser(
21760 _version: MavlinkVersion,
21761 __input: &[u8],
21762 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21763 let avail_len = __input.len();
21764 let mut payload_buf = [0; Self::ENCODED_LEN];
21765 let mut buf = if avail_len < Self::ENCODED_LEN {
21766 payload_buf[0..avail_len].copy_from_slice(__input);
21767 Bytes::new(&payload_buf)
21768 } else {
21769 Bytes::new(__input)
21770 };
21771 let mut __struct = Self::default();
21772 __struct.seq = buf.get_u16_le()?;
21773 __struct.target_system = buf.get_u8()?;
21774 __struct.target_component = buf.get_u8()?;
21775 let tmp = buf.get_u8()?;
21776 __struct.mission_type =
21777 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21778 enum_type: "MavMissionType",
21779 value: tmp as u64,
21780 })?;
21781 Ok(__struct)
21782 }
21783 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21784 let mut __tmp = BytesMut::new(bytes);
21785 #[allow(clippy::absurd_extreme_comparisons)]
21786 #[allow(unused_comparisons)]
21787 if __tmp.remaining() < Self::ENCODED_LEN {
21788 panic!(
21789 "buffer is too small (need {} bytes, but got {})",
21790 Self::ENCODED_LEN,
21791 __tmp.remaining(),
21792 )
21793 }
21794 __tmp.put_u16_le(self.seq);
21795 __tmp.put_u8(self.target_system);
21796 __tmp.put_u8(self.target_component);
21797 if matches!(version, MavlinkVersion::V2) {
21798 __tmp.put_u8(self.mission_type as u8);
21799 let len = __tmp.len();
21800 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21801 } else {
21802 __tmp.len()
21803 }
21804 }
21805}
21806#[doc = "Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM_INT message. <https://mavlink.io/en/services/mission.html>."]
21807#[doc = ""]
21808#[doc = "ID: 51"]
21809#[derive(Debug, Clone, PartialEq)]
21810#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21811#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21812#[cfg_attr(feature = "ts", derive(TS))]
21813#[cfg_attr(feature = "ts", ts(export))]
21814pub struct MISSION_REQUEST_INT_DATA {
21815 #[doc = "Sequence"]
21816 pub seq: u16,
21817 #[doc = "System ID"]
21818 pub target_system: u8,
21819 #[doc = "Component ID"]
21820 pub target_component: u8,
21821 #[doc = "Mission type."]
21822 #[cfg_attr(feature = "serde", serde(default))]
21823 pub mission_type: MavMissionType,
21824}
21825impl MISSION_REQUEST_INT_DATA {
21826 pub const ENCODED_LEN: usize = 5usize;
21827 pub const DEFAULT: Self = Self {
21828 seq: 0_u16,
21829 target_system: 0_u8,
21830 target_component: 0_u8,
21831 mission_type: MavMissionType::DEFAULT,
21832 };
21833 #[cfg(feature = "arbitrary")]
21834 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21835 use arbitrary::{Arbitrary, Unstructured};
21836 let mut buf = [0u8; 1024];
21837 rng.fill_bytes(&mut buf);
21838 let mut unstructured = Unstructured::new(&buf);
21839 Self::arbitrary(&mut unstructured).unwrap_or_default()
21840 }
21841}
21842impl Default for MISSION_REQUEST_INT_DATA {
21843 fn default() -> Self {
21844 Self::DEFAULT.clone()
21845 }
21846}
21847impl MessageData for MISSION_REQUEST_INT_DATA {
21848 type Message = MavMessage;
21849 const ID: u32 = 51u32;
21850 const NAME: &'static str = "MISSION_REQUEST_INT";
21851 const EXTRA_CRC: u8 = 196u8;
21852 const ENCODED_LEN: usize = 5usize;
21853 fn deser(
21854 _version: MavlinkVersion,
21855 __input: &[u8],
21856 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21857 let avail_len = __input.len();
21858 let mut payload_buf = [0; Self::ENCODED_LEN];
21859 let mut buf = if avail_len < Self::ENCODED_LEN {
21860 payload_buf[0..avail_len].copy_from_slice(__input);
21861 Bytes::new(&payload_buf)
21862 } else {
21863 Bytes::new(__input)
21864 };
21865 let mut __struct = Self::default();
21866 __struct.seq = buf.get_u16_le()?;
21867 __struct.target_system = buf.get_u8()?;
21868 __struct.target_component = buf.get_u8()?;
21869 let tmp = buf.get_u8()?;
21870 __struct.mission_type =
21871 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21872 enum_type: "MavMissionType",
21873 value: tmp as u64,
21874 })?;
21875 Ok(__struct)
21876 }
21877 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21878 let mut __tmp = BytesMut::new(bytes);
21879 #[allow(clippy::absurd_extreme_comparisons)]
21880 #[allow(unused_comparisons)]
21881 if __tmp.remaining() < Self::ENCODED_LEN {
21882 panic!(
21883 "buffer is too small (need {} bytes, but got {})",
21884 Self::ENCODED_LEN,
21885 __tmp.remaining(),
21886 )
21887 }
21888 __tmp.put_u16_le(self.seq);
21889 __tmp.put_u8(self.target_system);
21890 __tmp.put_u8(self.target_component);
21891 if matches!(version, MavlinkVersion::V2) {
21892 __tmp.put_u8(self.mission_type as u8);
21893 let len = __tmp.len();
21894 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21895 } else {
21896 __tmp.len()
21897 }
21898 }
21899}
21900#[doc = "Request the overall list of mission items from the system/component."]
21901#[doc = ""]
21902#[doc = "ID: 43"]
21903#[derive(Debug, Clone, PartialEq)]
21904#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21905#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21906#[cfg_attr(feature = "ts", derive(TS))]
21907#[cfg_attr(feature = "ts", ts(export))]
21908pub struct MISSION_REQUEST_LIST_DATA {
21909 #[doc = "System ID"]
21910 pub target_system: u8,
21911 #[doc = "Component ID"]
21912 pub target_component: u8,
21913 #[doc = "Mission type."]
21914 #[cfg_attr(feature = "serde", serde(default))]
21915 pub mission_type: MavMissionType,
21916}
21917impl MISSION_REQUEST_LIST_DATA {
21918 pub const ENCODED_LEN: usize = 3usize;
21919 pub const DEFAULT: Self = Self {
21920 target_system: 0_u8,
21921 target_component: 0_u8,
21922 mission_type: MavMissionType::DEFAULT,
21923 };
21924 #[cfg(feature = "arbitrary")]
21925 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21926 use arbitrary::{Arbitrary, Unstructured};
21927 let mut buf = [0u8; 1024];
21928 rng.fill_bytes(&mut buf);
21929 let mut unstructured = Unstructured::new(&buf);
21930 Self::arbitrary(&mut unstructured).unwrap_or_default()
21931 }
21932}
21933impl Default for MISSION_REQUEST_LIST_DATA {
21934 fn default() -> Self {
21935 Self::DEFAULT.clone()
21936 }
21937}
21938impl MessageData for MISSION_REQUEST_LIST_DATA {
21939 type Message = MavMessage;
21940 const ID: u32 = 43u32;
21941 const NAME: &'static str = "MISSION_REQUEST_LIST";
21942 const EXTRA_CRC: u8 = 132u8;
21943 const ENCODED_LEN: usize = 3usize;
21944 fn deser(
21945 _version: MavlinkVersion,
21946 __input: &[u8],
21947 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21948 let avail_len = __input.len();
21949 let mut payload_buf = [0; Self::ENCODED_LEN];
21950 let mut buf = if avail_len < Self::ENCODED_LEN {
21951 payload_buf[0..avail_len].copy_from_slice(__input);
21952 Bytes::new(&payload_buf)
21953 } else {
21954 Bytes::new(__input)
21955 };
21956 let mut __struct = Self::default();
21957 __struct.target_system = buf.get_u8()?;
21958 __struct.target_component = buf.get_u8()?;
21959 let tmp = buf.get_u8()?;
21960 __struct.mission_type =
21961 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21962 enum_type: "MavMissionType",
21963 value: tmp as u64,
21964 })?;
21965 Ok(__struct)
21966 }
21967 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21968 let mut __tmp = BytesMut::new(bytes);
21969 #[allow(clippy::absurd_extreme_comparisons)]
21970 #[allow(unused_comparisons)]
21971 if __tmp.remaining() < Self::ENCODED_LEN {
21972 panic!(
21973 "buffer is too small (need {} bytes, but got {})",
21974 Self::ENCODED_LEN,
21975 __tmp.remaining(),
21976 )
21977 }
21978 __tmp.put_u8(self.target_system);
21979 __tmp.put_u8(self.target_component);
21980 if matches!(version, MavlinkVersion::V2) {
21981 __tmp.put_u8(self.mission_type as u8);
21982 let len = __tmp.len();
21983 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21984 } else {
21985 __tmp.len()
21986 }
21987 }
21988}
21989#[doc = "Request a partial list of mission items from the system/component. <https://mavlink.io/en/services/mission.html>. If start and end index are the same, just send one waypoint."]
21990#[doc = ""]
21991#[doc = "ID: 37"]
21992#[derive(Debug, Clone, PartialEq)]
21993#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21994#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21995#[cfg_attr(feature = "ts", derive(TS))]
21996#[cfg_attr(feature = "ts", ts(export))]
21997pub struct MISSION_REQUEST_PARTIAL_LIST_DATA {
21998 #[doc = "Start index"]
21999 pub start_index: i16,
22000 #[doc = "End index, -1 by default (-1: send list to end). Else a valid index of the list"]
22001 pub end_index: i16,
22002 #[doc = "System ID"]
22003 pub target_system: u8,
22004 #[doc = "Component ID"]
22005 pub target_component: u8,
22006 #[doc = "Mission type."]
22007 #[cfg_attr(feature = "serde", serde(default))]
22008 pub mission_type: MavMissionType,
22009}
22010impl MISSION_REQUEST_PARTIAL_LIST_DATA {
22011 pub const ENCODED_LEN: usize = 7usize;
22012 pub const DEFAULT: Self = Self {
22013 start_index: 0_i16,
22014 end_index: 0_i16,
22015 target_system: 0_u8,
22016 target_component: 0_u8,
22017 mission_type: MavMissionType::DEFAULT,
22018 };
22019 #[cfg(feature = "arbitrary")]
22020 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22021 use arbitrary::{Arbitrary, Unstructured};
22022 let mut buf = [0u8; 1024];
22023 rng.fill_bytes(&mut buf);
22024 let mut unstructured = Unstructured::new(&buf);
22025 Self::arbitrary(&mut unstructured).unwrap_or_default()
22026 }
22027}
22028impl Default for MISSION_REQUEST_PARTIAL_LIST_DATA {
22029 fn default() -> Self {
22030 Self::DEFAULT.clone()
22031 }
22032}
22033impl MessageData for MISSION_REQUEST_PARTIAL_LIST_DATA {
22034 type Message = MavMessage;
22035 const ID: u32 = 37u32;
22036 const NAME: &'static str = "MISSION_REQUEST_PARTIAL_LIST";
22037 const EXTRA_CRC: u8 = 212u8;
22038 const ENCODED_LEN: usize = 7usize;
22039 fn deser(
22040 _version: MavlinkVersion,
22041 __input: &[u8],
22042 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22043 let avail_len = __input.len();
22044 let mut payload_buf = [0; Self::ENCODED_LEN];
22045 let mut buf = if avail_len < Self::ENCODED_LEN {
22046 payload_buf[0..avail_len].copy_from_slice(__input);
22047 Bytes::new(&payload_buf)
22048 } else {
22049 Bytes::new(__input)
22050 };
22051 let mut __struct = Self::default();
22052 __struct.start_index = buf.get_i16_le()?;
22053 __struct.end_index = buf.get_i16_le()?;
22054 __struct.target_system = buf.get_u8()?;
22055 __struct.target_component = buf.get_u8()?;
22056 let tmp = buf.get_u8()?;
22057 __struct.mission_type =
22058 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
22059 enum_type: "MavMissionType",
22060 value: tmp as u64,
22061 })?;
22062 Ok(__struct)
22063 }
22064 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22065 let mut __tmp = BytesMut::new(bytes);
22066 #[allow(clippy::absurd_extreme_comparisons)]
22067 #[allow(unused_comparisons)]
22068 if __tmp.remaining() < Self::ENCODED_LEN {
22069 panic!(
22070 "buffer is too small (need {} bytes, but got {})",
22071 Self::ENCODED_LEN,
22072 __tmp.remaining(),
22073 )
22074 }
22075 __tmp.put_i16_le(self.start_index);
22076 __tmp.put_i16_le(self.end_index);
22077 __tmp.put_u8(self.target_system);
22078 __tmp.put_u8(self.target_component);
22079 if matches!(version, MavlinkVersion::V2) {
22080 __tmp.put_u8(self.mission_type as u8);
22081 let len = __tmp.len();
22082 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22083 } else {
22084 __tmp.len()
22085 }
22086 }
22087}
22088#[deprecated = " See `MAV_CMD_DO_SET_MISSION_CURRENT` (Deprecated since 2022-08)"]
22089#[doc = "Set the mission item with sequence number seq as the current item and emit MISSION_CURRENT (whether or not the mission number changed). If a mission is currently being executed, the system will continue to this new mission item on the shortest path, skipping any intermediate mission items. Note that mission jump repeat counters are not reset (see MAV_CMD_DO_JUMP param2). This message may trigger a mission state-machine change on some systems: for example from MISSION_STATE_NOT_STARTED or MISSION_STATE_PAUSED to MISSION_STATE_ACTIVE. If the system is in mission mode, on those systems this command might therefore start, restart or resume the mission. If the system is not in mission mode this message must not trigger a switch to mission mode."]
22090#[doc = ""]
22091#[doc = "ID: 41"]
22092#[derive(Debug, Clone, PartialEq)]
22093#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22094#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22095#[cfg_attr(feature = "ts", derive(TS))]
22096#[cfg_attr(feature = "ts", ts(export))]
22097pub struct MISSION_SET_CURRENT_DATA {
22098 #[doc = "Sequence"]
22099 pub seq: u16,
22100 #[doc = "System ID"]
22101 pub target_system: u8,
22102 #[doc = "Component ID"]
22103 pub target_component: u8,
22104}
22105impl MISSION_SET_CURRENT_DATA {
22106 pub const ENCODED_LEN: usize = 4usize;
22107 pub const DEFAULT: Self = Self {
22108 seq: 0_u16,
22109 target_system: 0_u8,
22110 target_component: 0_u8,
22111 };
22112 #[cfg(feature = "arbitrary")]
22113 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22114 use arbitrary::{Arbitrary, Unstructured};
22115 let mut buf = [0u8; 1024];
22116 rng.fill_bytes(&mut buf);
22117 let mut unstructured = Unstructured::new(&buf);
22118 Self::arbitrary(&mut unstructured).unwrap_or_default()
22119 }
22120}
22121impl Default for MISSION_SET_CURRENT_DATA {
22122 fn default() -> Self {
22123 Self::DEFAULT.clone()
22124 }
22125}
22126impl MessageData for MISSION_SET_CURRENT_DATA {
22127 type Message = MavMessage;
22128 const ID: u32 = 41u32;
22129 const NAME: &'static str = "MISSION_SET_CURRENT";
22130 const EXTRA_CRC: u8 = 28u8;
22131 const ENCODED_LEN: usize = 4usize;
22132 fn deser(
22133 _version: MavlinkVersion,
22134 __input: &[u8],
22135 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22136 let avail_len = __input.len();
22137 let mut payload_buf = [0; Self::ENCODED_LEN];
22138 let mut buf = if avail_len < Self::ENCODED_LEN {
22139 payload_buf[0..avail_len].copy_from_slice(__input);
22140 Bytes::new(&payload_buf)
22141 } else {
22142 Bytes::new(__input)
22143 };
22144 let mut __struct = Self::default();
22145 __struct.seq = buf.get_u16_le()?;
22146 __struct.target_system = buf.get_u8()?;
22147 __struct.target_component = buf.get_u8()?;
22148 Ok(__struct)
22149 }
22150 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22151 let mut __tmp = BytesMut::new(bytes);
22152 #[allow(clippy::absurd_extreme_comparisons)]
22153 #[allow(unused_comparisons)]
22154 if __tmp.remaining() < Self::ENCODED_LEN {
22155 panic!(
22156 "buffer is too small (need {} bytes, but got {})",
22157 Self::ENCODED_LEN,
22158 __tmp.remaining(),
22159 )
22160 }
22161 __tmp.put_u16_le(self.seq);
22162 __tmp.put_u8(self.target_system);
22163 __tmp.put_u8(self.target_component);
22164 if matches!(version, MavlinkVersion::V2) {
22165 let len = __tmp.len();
22166 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22167 } else {
22168 __tmp.len()
22169 }
22170 }
22171}
22172#[doc = "This message is sent to the MAV to write a partial list. If start index == end index, only one item will be transmitted / updated. If the start index is NOT 0 and above the current list size, this request should be REJECTED!."]
22173#[doc = ""]
22174#[doc = "ID: 38"]
22175#[derive(Debug, Clone, PartialEq)]
22176#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22177#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22178#[cfg_attr(feature = "ts", derive(TS))]
22179#[cfg_attr(feature = "ts", ts(export))]
22180pub struct MISSION_WRITE_PARTIAL_LIST_DATA {
22181 #[doc = "Start index. Must be smaller / equal to the largest index of the current onboard list."]
22182 pub start_index: i16,
22183 #[doc = "End index, equal or greater than start index."]
22184 pub end_index: i16,
22185 #[doc = "System ID"]
22186 pub target_system: u8,
22187 #[doc = "Component ID"]
22188 pub target_component: u8,
22189 #[doc = "Mission type."]
22190 #[cfg_attr(feature = "serde", serde(default))]
22191 pub mission_type: MavMissionType,
22192}
22193impl MISSION_WRITE_PARTIAL_LIST_DATA {
22194 pub const ENCODED_LEN: usize = 7usize;
22195 pub const DEFAULT: Self = Self {
22196 start_index: 0_i16,
22197 end_index: 0_i16,
22198 target_system: 0_u8,
22199 target_component: 0_u8,
22200 mission_type: MavMissionType::DEFAULT,
22201 };
22202 #[cfg(feature = "arbitrary")]
22203 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22204 use arbitrary::{Arbitrary, Unstructured};
22205 let mut buf = [0u8; 1024];
22206 rng.fill_bytes(&mut buf);
22207 let mut unstructured = Unstructured::new(&buf);
22208 Self::arbitrary(&mut unstructured).unwrap_or_default()
22209 }
22210}
22211impl Default for MISSION_WRITE_PARTIAL_LIST_DATA {
22212 fn default() -> Self {
22213 Self::DEFAULT.clone()
22214 }
22215}
22216impl MessageData for MISSION_WRITE_PARTIAL_LIST_DATA {
22217 type Message = MavMessage;
22218 const ID: u32 = 38u32;
22219 const NAME: &'static str = "MISSION_WRITE_PARTIAL_LIST";
22220 const EXTRA_CRC: u8 = 9u8;
22221 const ENCODED_LEN: usize = 7usize;
22222 fn deser(
22223 _version: MavlinkVersion,
22224 __input: &[u8],
22225 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22226 let avail_len = __input.len();
22227 let mut payload_buf = [0; Self::ENCODED_LEN];
22228 let mut buf = if avail_len < Self::ENCODED_LEN {
22229 payload_buf[0..avail_len].copy_from_slice(__input);
22230 Bytes::new(&payload_buf)
22231 } else {
22232 Bytes::new(__input)
22233 };
22234 let mut __struct = Self::default();
22235 __struct.start_index = buf.get_i16_le()?;
22236 __struct.end_index = buf.get_i16_le()?;
22237 __struct.target_system = buf.get_u8()?;
22238 __struct.target_component = buf.get_u8()?;
22239 let tmp = buf.get_u8()?;
22240 __struct.mission_type =
22241 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
22242 enum_type: "MavMissionType",
22243 value: tmp as u64,
22244 })?;
22245 Ok(__struct)
22246 }
22247 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22248 let mut __tmp = BytesMut::new(bytes);
22249 #[allow(clippy::absurd_extreme_comparisons)]
22250 #[allow(unused_comparisons)]
22251 if __tmp.remaining() < Self::ENCODED_LEN {
22252 panic!(
22253 "buffer is too small (need {} bytes, but got {})",
22254 Self::ENCODED_LEN,
22255 __tmp.remaining(),
22256 )
22257 }
22258 __tmp.put_i16_le(self.start_index);
22259 __tmp.put_i16_le(self.end_index);
22260 __tmp.put_u8(self.target_system);
22261 __tmp.put_u8(self.target_component);
22262 if matches!(version, MavlinkVersion::V2) {
22263 __tmp.put_u8(self.mission_type as u8);
22264 let len = __tmp.len();
22265 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22266 } else {
22267 __tmp.len()
22268 }
22269 }
22270}
22271#[deprecated = "This message is being superseded by MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW. The message can still be used to communicate with legacy gimbals implementing it. See `MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW` (Deprecated since 2020-01)"]
22272#[doc = "Orientation of a mount."]
22273#[doc = ""]
22274#[doc = "ID: 265"]
22275#[derive(Debug, Clone, PartialEq)]
22276#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22277#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22278#[cfg_attr(feature = "ts", derive(TS))]
22279#[cfg_attr(feature = "ts", ts(export))]
22280pub struct MOUNT_ORIENTATION_DATA {
22281 #[doc = "Timestamp (time since system boot)."]
22282 pub time_boot_ms: u32,
22283 #[doc = "Roll in global frame (set to NaN for invalid)."]
22284 pub roll: f32,
22285 #[doc = "Pitch in global frame (set to NaN for invalid)."]
22286 pub pitch: f32,
22287 #[doc = "Yaw relative to vehicle (set to NaN for invalid)."]
22288 pub yaw: f32,
22289 #[doc = "Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid)."]
22290 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
22291 pub yaw_absolute: f32,
22292}
22293impl MOUNT_ORIENTATION_DATA {
22294 pub const ENCODED_LEN: usize = 20usize;
22295 pub const DEFAULT: Self = Self {
22296 time_boot_ms: 0_u32,
22297 roll: 0.0_f32,
22298 pitch: 0.0_f32,
22299 yaw: 0.0_f32,
22300 yaw_absolute: 0.0_f32,
22301 };
22302 #[cfg(feature = "arbitrary")]
22303 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22304 use arbitrary::{Arbitrary, Unstructured};
22305 let mut buf = [0u8; 1024];
22306 rng.fill_bytes(&mut buf);
22307 let mut unstructured = Unstructured::new(&buf);
22308 Self::arbitrary(&mut unstructured).unwrap_or_default()
22309 }
22310}
22311impl Default for MOUNT_ORIENTATION_DATA {
22312 fn default() -> Self {
22313 Self::DEFAULT.clone()
22314 }
22315}
22316impl MessageData for MOUNT_ORIENTATION_DATA {
22317 type Message = MavMessage;
22318 const ID: u32 = 265u32;
22319 const NAME: &'static str = "MOUNT_ORIENTATION";
22320 const EXTRA_CRC: u8 = 26u8;
22321 const ENCODED_LEN: usize = 20usize;
22322 fn deser(
22323 _version: MavlinkVersion,
22324 __input: &[u8],
22325 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22326 let avail_len = __input.len();
22327 let mut payload_buf = [0; Self::ENCODED_LEN];
22328 let mut buf = if avail_len < Self::ENCODED_LEN {
22329 payload_buf[0..avail_len].copy_from_slice(__input);
22330 Bytes::new(&payload_buf)
22331 } else {
22332 Bytes::new(__input)
22333 };
22334 let mut __struct = Self::default();
22335 __struct.time_boot_ms = buf.get_u32_le()?;
22336 __struct.roll = buf.get_f32_le()?;
22337 __struct.pitch = buf.get_f32_le()?;
22338 __struct.yaw = buf.get_f32_le()?;
22339 __struct.yaw_absolute = buf.get_f32_le()?;
22340 Ok(__struct)
22341 }
22342 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22343 let mut __tmp = BytesMut::new(bytes);
22344 #[allow(clippy::absurd_extreme_comparisons)]
22345 #[allow(unused_comparisons)]
22346 if __tmp.remaining() < Self::ENCODED_LEN {
22347 panic!(
22348 "buffer is too small (need {} bytes, but got {})",
22349 Self::ENCODED_LEN,
22350 __tmp.remaining(),
22351 )
22352 }
22353 __tmp.put_u32_le(self.time_boot_ms);
22354 __tmp.put_f32_le(self.roll);
22355 __tmp.put_f32_le(self.pitch);
22356 __tmp.put_f32_le(self.yaw);
22357 if matches!(version, MavlinkVersion::V2) {
22358 __tmp.put_f32_le(self.yaw_absolute);
22359 let len = __tmp.len();
22360 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22361 } else {
22362 __tmp.len()
22363 }
22364 }
22365}
22366#[doc = "Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output."]
22367#[doc = ""]
22368#[doc = "ID: 251"]
22369#[derive(Debug, Clone, PartialEq)]
22370#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22371#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22372#[cfg_attr(feature = "ts", derive(TS))]
22373#[cfg_attr(feature = "ts", ts(export))]
22374pub struct NAMED_VALUE_FLOAT_DATA {
22375 #[doc = "Timestamp (time since system boot)."]
22376 pub time_boot_ms: u32,
22377 #[doc = "Floating point value"]
22378 pub value: f32,
22379 #[doc = "Name of the debug variable"]
22380 #[cfg_attr(feature = "ts", ts(type = "string"))]
22381 pub name: CharArray<10>,
22382}
22383impl NAMED_VALUE_FLOAT_DATA {
22384 pub const ENCODED_LEN: usize = 18usize;
22385 pub const DEFAULT: Self = Self {
22386 time_boot_ms: 0_u32,
22387 value: 0.0_f32,
22388 name: CharArray::new([0_u8; 10usize]),
22389 };
22390 #[cfg(feature = "arbitrary")]
22391 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22392 use arbitrary::{Arbitrary, Unstructured};
22393 let mut buf = [0u8; 1024];
22394 rng.fill_bytes(&mut buf);
22395 let mut unstructured = Unstructured::new(&buf);
22396 Self::arbitrary(&mut unstructured).unwrap_or_default()
22397 }
22398}
22399impl Default for NAMED_VALUE_FLOAT_DATA {
22400 fn default() -> Self {
22401 Self::DEFAULT.clone()
22402 }
22403}
22404impl MessageData for NAMED_VALUE_FLOAT_DATA {
22405 type Message = MavMessage;
22406 const ID: u32 = 251u32;
22407 const NAME: &'static str = "NAMED_VALUE_FLOAT";
22408 const EXTRA_CRC: u8 = 170u8;
22409 const ENCODED_LEN: usize = 18usize;
22410 fn deser(
22411 _version: MavlinkVersion,
22412 __input: &[u8],
22413 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22414 let avail_len = __input.len();
22415 let mut payload_buf = [0; Self::ENCODED_LEN];
22416 let mut buf = if avail_len < Self::ENCODED_LEN {
22417 payload_buf[0..avail_len].copy_from_slice(__input);
22418 Bytes::new(&payload_buf)
22419 } else {
22420 Bytes::new(__input)
22421 };
22422 let mut __struct = Self::default();
22423 __struct.time_boot_ms = buf.get_u32_le()?;
22424 __struct.value = buf.get_f32_le()?;
22425 let mut tmp = [0_u8; 10usize];
22426 for v in &mut tmp {
22427 *v = buf.get_u8()?;
22428 }
22429 __struct.name = CharArray::new(tmp);
22430 Ok(__struct)
22431 }
22432 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22433 let mut __tmp = BytesMut::new(bytes);
22434 #[allow(clippy::absurd_extreme_comparisons)]
22435 #[allow(unused_comparisons)]
22436 if __tmp.remaining() < Self::ENCODED_LEN {
22437 panic!(
22438 "buffer is too small (need {} bytes, but got {})",
22439 Self::ENCODED_LEN,
22440 __tmp.remaining(),
22441 )
22442 }
22443 __tmp.put_u32_le(self.time_boot_ms);
22444 __tmp.put_f32_le(self.value);
22445 for val in &self.name {
22446 __tmp.put_u8(*val);
22447 }
22448 if matches!(version, MavlinkVersion::V2) {
22449 let len = __tmp.len();
22450 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22451 } else {
22452 __tmp.len()
22453 }
22454 }
22455}
22456#[doc = "Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output."]
22457#[doc = ""]
22458#[doc = "ID: 252"]
22459#[derive(Debug, Clone, PartialEq)]
22460#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22461#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22462#[cfg_attr(feature = "ts", derive(TS))]
22463#[cfg_attr(feature = "ts", ts(export))]
22464pub struct NAMED_VALUE_INT_DATA {
22465 #[doc = "Timestamp (time since system boot)."]
22466 pub time_boot_ms: u32,
22467 #[doc = "Signed integer value"]
22468 pub value: i32,
22469 #[doc = "Name of the debug variable"]
22470 #[cfg_attr(feature = "ts", ts(type = "string"))]
22471 pub name: CharArray<10>,
22472}
22473impl NAMED_VALUE_INT_DATA {
22474 pub const ENCODED_LEN: usize = 18usize;
22475 pub const DEFAULT: Self = Self {
22476 time_boot_ms: 0_u32,
22477 value: 0_i32,
22478 name: CharArray::new([0_u8; 10usize]),
22479 };
22480 #[cfg(feature = "arbitrary")]
22481 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22482 use arbitrary::{Arbitrary, Unstructured};
22483 let mut buf = [0u8; 1024];
22484 rng.fill_bytes(&mut buf);
22485 let mut unstructured = Unstructured::new(&buf);
22486 Self::arbitrary(&mut unstructured).unwrap_or_default()
22487 }
22488}
22489impl Default for NAMED_VALUE_INT_DATA {
22490 fn default() -> Self {
22491 Self::DEFAULT.clone()
22492 }
22493}
22494impl MessageData for NAMED_VALUE_INT_DATA {
22495 type Message = MavMessage;
22496 const ID: u32 = 252u32;
22497 const NAME: &'static str = "NAMED_VALUE_INT";
22498 const EXTRA_CRC: u8 = 44u8;
22499 const ENCODED_LEN: usize = 18usize;
22500 fn deser(
22501 _version: MavlinkVersion,
22502 __input: &[u8],
22503 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22504 let avail_len = __input.len();
22505 let mut payload_buf = [0; Self::ENCODED_LEN];
22506 let mut buf = if avail_len < Self::ENCODED_LEN {
22507 payload_buf[0..avail_len].copy_from_slice(__input);
22508 Bytes::new(&payload_buf)
22509 } else {
22510 Bytes::new(__input)
22511 };
22512 let mut __struct = Self::default();
22513 __struct.time_boot_ms = buf.get_u32_le()?;
22514 __struct.value = buf.get_i32_le()?;
22515 let mut tmp = [0_u8; 10usize];
22516 for v in &mut tmp {
22517 *v = buf.get_u8()?;
22518 }
22519 __struct.name = CharArray::new(tmp);
22520 Ok(__struct)
22521 }
22522 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22523 let mut __tmp = BytesMut::new(bytes);
22524 #[allow(clippy::absurd_extreme_comparisons)]
22525 #[allow(unused_comparisons)]
22526 if __tmp.remaining() < Self::ENCODED_LEN {
22527 panic!(
22528 "buffer is too small (need {} bytes, but got {})",
22529 Self::ENCODED_LEN,
22530 __tmp.remaining(),
22531 )
22532 }
22533 __tmp.put_u32_le(self.time_boot_ms);
22534 __tmp.put_i32_le(self.value);
22535 for val in &self.name {
22536 __tmp.put_u8(*val);
22537 }
22538 if matches!(version, MavlinkVersion::V2) {
22539 let len = __tmp.len();
22540 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22541 } else {
22542 __tmp.len()
22543 }
22544 }
22545}
22546#[doc = "The state of the navigation and position controller."]
22547#[doc = ""]
22548#[doc = "ID: 62"]
22549#[derive(Debug, Clone, PartialEq)]
22550#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22551#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22552#[cfg_attr(feature = "ts", derive(TS))]
22553#[cfg_attr(feature = "ts", ts(export))]
22554pub struct NAV_CONTROLLER_OUTPUT_DATA {
22555 #[doc = "Current desired roll"]
22556 pub nav_roll: f32,
22557 #[doc = "Current desired pitch"]
22558 pub nav_pitch: f32,
22559 #[doc = "Current altitude error"]
22560 pub alt_error: f32,
22561 #[doc = "Current airspeed error"]
22562 pub aspd_error: f32,
22563 #[doc = "Current crosstrack error on x-y plane"]
22564 pub xtrack_error: f32,
22565 #[doc = "Current desired heading"]
22566 pub nav_bearing: i16,
22567 #[doc = "Bearing to current waypoint/target"]
22568 pub target_bearing: i16,
22569 #[doc = "Distance to active waypoint"]
22570 pub wp_dist: u16,
22571}
22572impl NAV_CONTROLLER_OUTPUT_DATA {
22573 pub const ENCODED_LEN: usize = 26usize;
22574 pub const DEFAULT: Self = Self {
22575 nav_roll: 0.0_f32,
22576 nav_pitch: 0.0_f32,
22577 alt_error: 0.0_f32,
22578 aspd_error: 0.0_f32,
22579 xtrack_error: 0.0_f32,
22580 nav_bearing: 0_i16,
22581 target_bearing: 0_i16,
22582 wp_dist: 0_u16,
22583 };
22584 #[cfg(feature = "arbitrary")]
22585 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22586 use arbitrary::{Arbitrary, Unstructured};
22587 let mut buf = [0u8; 1024];
22588 rng.fill_bytes(&mut buf);
22589 let mut unstructured = Unstructured::new(&buf);
22590 Self::arbitrary(&mut unstructured).unwrap_or_default()
22591 }
22592}
22593impl Default for NAV_CONTROLLER_OUTPUT_DATA {
22594 fn default() -> Self {
22595 Self::DEFAULT.clone()
22596 }
22597}
22598impl MessageData for NAV_CONTROLLER_OUTPUT_DATA {
22599 type Message = MavMessage;
22600 const ID: u32 = 62u32;
22601 const NAME: &'static str = "NAV_CONTROLLER_OUTPUT";
22602 const EXTRA_CRC: u8 = 183u8;
22603 const ENCODED_LEN: usize = 26usize;
22604 fn deser(
22605 _version: MavlinkVersion,
22606 __input: &[u8],
22607 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22608 let avail_len = __input.len();
22609 let mut payload_buf = [0; Self::ENCODED_LEN];
22610 let mut buf = if avail_len < Self::ENCODED_LEN {
22611 payload_buf[0..avail_len].copy_from_slice(__input);
22612 Bytes::new(&payload_buf)
22613 } else {
22614 Bytes::new(__input)
22615 };
22616 let mut __struct = Self::default();
22617 __struct.nav_roll = buf.get_f32_le()?;
22618 __struct.nav_pitch = buf.get_f32_le()?;
22619 __struct.alt_error = buf.get_f32_le()?;
22620 __struct.aspd_error = buf.get_f32_le()?;
22621 __struct.xtrack_error = buf.get_f32_le()?;
22622 __struct.nav_bearing = buf.get_i16_le()?;
22623 __struct.target_bearing = buf.get_i16_le()?;
22624 __struct.wp_dist = buf.get_u16_le()?;
22625 Ok(__struct)
22626 }
22627 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22628 let mut __tmp = BytesMut::new(bytes);
22629 #[allow(clippy::absurd_extreme_comparisons)]
22630 #[allow(unused_comparisons)]
22631 if __tmp.remaining() < Self::ENCODED_LEN {
22632 panic!(
22633 "buffer is too small (need {} bytes, but got {})",
22634 Self::ENCODED_LEN,
22635 __tmp.remaining(),
22636 )
22637 }
22638 __tmp.put_f32_le(self.nav_roll);
22639 __tmp.put_f32_le(self.nav_pitch);
22640 __tmp.put_f32_le(self.alt_error);
22641 __tmp.put_f32_le(self.aspd_error);
22642 __tmp.put_f32_le(self.xtrack_error);
22643 __tmp.put_i16_le(self.nav_bearing);
22644 __tmp.put_i16_le(self.target_bearing);
22645 __tmp.put_u16_le(self.wp_dist);
22646 if matches!(version, MavlinkVersion::V2) {
22647 let len = __tmp.len();
22648 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22649 } else {
22650 __tmp.len()
22651 }
22652 }
22653}
22654#[doc = "Obstacle distances in front of the sensor, starting from the left in increment degrees to the right."]
22655#[doc = ""]
22656#[doc = "ID: 330"]
22657#[derive(Debug, Clone, PartialEq)]
22658#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22659#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22660#[cfg_attr(feature = "ts", derive(TS))]
22661#[cfg_attr(feature = "ts", ts(export))]
22662pub struct OBSTACLE_DISTANCE_DATA {
22663 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
22664 pub time_usec: u64,
22665 #[doc = "Distance of obstacles around the vehicle with index 0 corresponding to north + angle_offset, unless otherwise specified in the frame. A value of 0 is valid and means that the obstacle is practically touching the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm."]
22666 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
22667 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
22668 pub distances: [u16; 72],
22669 #[doc = "Minimum distance the sensor can measure."]
22670 pub min_distance: u16,
22671 #[doc = "Maximum distance the sensor can measure."]
22672 pub max_distance: u16,
22673 #[doc = "Class id of the distance sensor type."]
22674 pub sensor_type: MavDistanceSensor,
22675 #[doc = "Angular width in degrees of each array element. Increment direction is clockwise. This field is ignored if increment_f is non-zero."]
22676 pub increment: u8,
22677 #[doc = "Angular width in degrees of each array element as a float. If non-zero then this value is used instead of the uint8_t increment field. Positive is clockwise direction, negative is counter-clockwise."]
22678 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
22679 pub increment_f: f32,
22680 #[doc = "Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise."]
22681 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
22682 pub angle_offset: f32,
22683 #[doc = "Coordinate frame of reference for the yaw rotation and offset of the sensor data. Defaults to MAV_FRAME_GLOBAL, which is north aligned. For body-mounted sensors use MAV_FRAME_BODY_FRD, which is vehicle front aligned."]
22684 #[cfg_attr(feature = "serde", serde(default))]
22685 pub frame: MavFrame,
22686}
22687impl OBSTACLE_DISTANCE_DATA {
22688 pub const ENCODED_LEN: usize = 167usize;
22689 pub const DEFAULT: Self = Self {
22690 time_usec: 0_u64,
22691 distances: [0_u16; 72usize],
22692 min_distance: 0_u16,
22693 max_distance: 0_u16,
22694 sensor_type: MavDistanceSensor::DEFAULT,
22695 increment: 0_u8,
22696 increment_f: 0.0_f32,
22697 angle_offset: 0.0_f32,
22698 frame: MavFrame::DEFAULT,
22699 };
22700 #[cfg(feature = "arbitrary")]
22701 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22702 use arbitrary::{Arbitrary, Unstructured};
22703 let mut buf = [0u8; 1024];
22704 rng.fill_bytes(&mut buf);
22705 let mut unstructured = Unstructured::new(&buf);
22706 Self::arbitrary(&mut unstructured).unwrap_or_default()
22707 }
22708}
22709impl Default for OBSTACLE_DISTANCE_DATA {
22710 fn default() -> Self {
22711 Self::DEFAULT.clone()
22712 }
22713}
22714impl MessageData for OBSTACLE_DISTANCE_DATA {
22715 type Message = MavMessage;
22716 const ID: u32 = 330u32;
22717 const NAME: &'static str = "OBSTACLE_DISTANCE";
22718 const EXTRA_CRC: u8 = 23u8;
22719 const ENCODED_LEN: usize = 167usize;
22720 fn deser(
22721 _version: MavlinkVersion,
22722 __input: &[u8],
22723 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22724 let avail_len = __input.len();
22725 let mut payload_buf = [0; Self::ENCODED_LEN];
22726 let mut buf = if avail_len < Self::ENCODED_LEN {
22727 payload_buf[0..avail_len].copy_from_slice(__input);
22728 Bytes::new(&payload_buf)
22729 } else {
22730 Bytes::new(__input)
22731 };
22732 let mut __struct = Self::default();
22733 __struct.time_usec = buf.get_u64_le()?;
22734 for v in &mut __struct.distances {
22735 let val = buf.get_u16_le()?;
22736 *v = val;
22737 }
22738 __struct.min_distance = buf.get_u16_le()?;
22739 __struct.max_distance = buf.get_u16_le()?;
22740 let tmp = buf.get_u8()?;
22741 __struct.sensor_type =
22742 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
22743 enum_type: "MavDistanceSensor",
22744 value: tmp as u64,
22745 })?;
22746 __struct.increment = buf.get_u8()?;
22747 __struct.increment_f = buf.get_f32_le()?;
22748 __struct.angle_offset = buf.get_f32_le()?;
22749 let tmp = buf.get_u8()?;
22750 __struct.frame =
22751 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
22752 enum_type: "MavFrame",
22753 value: tmp as u64,
22754 })?;
22755 Ok(__struct)
22756 }
22757 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22758 let mut __tmp = BytesMut::new(bytes);
22759 #[allow(clippy::absurd_extreme_comparisons)]
22760 #[allow(unused_comparisons)]
22761 if __tmp.remaining() < Self::ENCODED_LEN {
22762 panic!(
22763 "buffer is too small (need {} bytes, but got {})",
22764 Self::ENCODED_LEN,
22765 __tmp.remaining(),
22766 )
22767 }
22768 __tmp.put_u64_le(self.time_usec);
22769 for val in &self.distances {
22770 __tmp.put_u16_le(*val);
22771 }
22772 __tmp.put_u16_le(self.min_distance);
22773 __tmp.put_u16_le(self.max_distance);
22774 __tmp.put_u8(self.sensor_type as u8);
22775 __tmp.put_u8(self.increment);
22776 if matches!(version, MavlinkVersion::V2) {
22777 __tmp.put_f32_le(self.increment_f);
22778 __tmp.put_f32_le(self.angle_offset);
22779 __tmp.put_u8(self.frame as u8);
22780 let len = __tmp.len();
22781 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22782 } else {
22783 __tmp.len()
22784 }
22785 }
22786}
22787#[doc = "Odometry message to communicate odometry information with an external interface. Fits ROS REP 147 standard for aerial vehicles (<http://www.ros.org/reps/rep-0147.html>)."]
22788#[doc = ""]
22789#[doc = "ID: 331"]
22790#[derive(Debug, Clone, PartialEq)]
22791#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22792#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22793#[cfg_attr(feature = "ts", derive(TS))]
22794#[cfg_attr(feature = "ts", ts(export))]
22795pub struct ODOMETRY_DATA {
22796 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
22797 pub time_usec: u64,
22798 #[doc = "X Position"]
22799 pub x: f32,
22800 #[doc = "Y Position"]
22801 pub y: f32,
22802 #[doc = "Z Position"]
22803 pub z: f32,
22804 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)"]
22805 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
22806 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
22807 pub q: [f32; 4],
22808 #[doc = "X linear speed"]
22809 pub vx: f32,
22810 #[doc = "Y linear speed"]
22811 pub vy: f32,
22812 #[doc = "Z linear speed"]
22813 pub vz: f32,
22814 #[doc = "Roll angular speed"]
22815 pub rollspeed: f32,
22816 #[doc = "Pitch angular speed"]
22817 pub pitchspeed: f32,
22818 #[doc = "Yaw angular speed"]
22819 pub yawspeed: f32,
22820 #[doc = "Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
22821 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
22822 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
22823 pub pose_covariance: [f32; 21],
22824 #[doc = "Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
22825 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
22826 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
22827 pub velocity_covariance: [f32; 21],
22828 #[doc = "Coordinate frame of reference for the pose data."]
22829 pub frame_id: MavFrame,
22830 #[doc = "Coordinate frame of reference for the velocity in free space (twist) data."]
22831 pub child_frame_id: MavFrame,
22832 #[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps."]
22833 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
22834 pub reset_counter: u8,
22835 #[doc = "Type of estimator that is providing the odometry."]
22836 #[cfg_attr(feature = "serde", serde(default))]
22837 pub estimator_type: MavEstimatorType,
22838 #[doc = "Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality"]
22839 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
22840 pub quality: i8,
22841}
22842impl ODOMETRY_DATA {
22843 pub const ENCODED_LEN: usize = 233usize;
22844 pub const DEFAULT: Self = Self {
22845 time_usec: 0_u64,
22846 x: 0.0_f32,
22847 y: 0.0_f32,
22848 z: 0.0_f32,
22849 q: [0.0_f32; 4usize],
22850 vx: 0.0_f32,
22851 vy: 0.0_f32,
22852 vz: 0.0_f32,
22853 rollspeed: 0.0_f32,
22854 pitchspeed: 0.0_f32,
22855 yawspeed: 0.0_f32,
22856 pose_covariance: [0.0_f32; 21usize],
22857 velocity_covariance: [0.0_f32; 21usize],
22858 frame_id: MavFrame::DEFAULT,
22859 child_frame_id: MavFrame::DEFAULT,
22860 reset_counter: 0_u8,
22861 estimator_type: MavEstimatorType::DEFAULT,
22862 quality: 0_i8,
22863 };
22864 #[cfg(feature = "arbitrary")]
22865 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22866 use arbitrary::{Arbitrary, Unstructured};
22867 let mut buf = [0u8; 1024];
22868 rng.fill_bytes(&mut buf);
22869 let mut unstructured = Unstructured::new(&buf);
22870 Self::arbitrary(&mut unstructured).unwrap_or_default()
22871 }
22872}
22873impl Default for ODOMETRY_DATA {
22874 fn default() -> Self {
22875 Self::DEFAULT.clone()
22876 }
22877}
22878impl MessageData for ODOMETRY_DATA {
22879 type Message = MavMessage;
22880 const ID: u32 = 331u32;
22881 const NAME: &'static str = "ODOMETRY";
22882 const EXTRA_CRC: u8 = 91u8;
22883 const ENCODED_LEN: usize = 233usize;
22884 fn deser(
22885 _version: MavlinkVersion,
22886 __input: &[u8],
22887 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22888 let avail_len = __input.len();
22889 let mut payload_buf = [0; Self::ENCODED_LEN];
22890 let mut buf = if avail_len < Self::ENCODED_LEN {
22891 payload_buf[0..avail_len].copy_from_slice(__input);
22892 Bytes::new(&payload_buf)
22893 } else {
22894 Bytes::new(__input)
22895 };
22896 let mut __struct = Self::default();
22897 __struct.time_usec = buf.get_u64_le()?;
22898 __struct.x = buf.get_f32_le()?;
22899 __struct.y = buf.get_f32_le()?;
22900 __struct.z = buf.get_f32_le()?;
22901 for v in &mut __struct.q {
22902 let val = buf.get_f32_le()?;
22903 *v = val;
22904 }
22905 __struct.vx = buf.get_f32_le()?;
22906 __struct.vy = buf.get_f32_le()?;
22907 __struct.vz = buf.get_f32_le()?;
22908 __struct.rollspeed = buf.get_f32_le()?;
22909 __struct.pitchspeed = buf.get_f32_le()?;
22910 __struct.yawspeed = buf.get_f32_le()?;
22911 for v in &mut __struct.pose_covariance {
22912 let val = buf.get_f32_le()?;
22913 *v = val;
22914 }
22915 for v in &mut __struct.velocity_covariance {
22916 let val = buf.get_f32_le()?;
22917 *v = val;
22918 }
22919 let tmp = buf.get_u8()?;
22920 __struct.frame_id =
22921 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
22922 enum_type: "MavFrame",
22923 value: tmp as u64,
22924 })?;
22925 let tmp = buf.get_u8()?;
22926 __struct.child_frame_id =
22927 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
22928 enum_type: "MavFrame",
22929 value: tmp as u64,
22930 })?;
22931 __struct.reset_counter = buf.get_u8()?;
22932 let tmp = buf.get_u8()?;
22933 __struct.estimator_type =
22934 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
22935 enum_type: "MavEstimatorType",
22936 value: tmp as u64,
22937 })?;
22938 __struct.quality = buf.get_i8()?;
22939 Ok(__struct)
22940 }
22941 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22942 let mut __tmp = BytesMut::new(bytes);
22943 #[allow(clippy::absurd_extreme_comparisons)]
22944 #[allow(unused_comparisons)]
22945 if __tmp.remaining() < Self::ENCODED_LEN {
22946 panic!(
22947 "buffer is too small (need {} bytes, but got {})",
22948 Self::ENCODED_LEN,
22949 __tmp.remaining(),
22950 )
22951 }
22952 __tmp.put_u64_le(self.time_usec);
22953 __tmp.put_f32_le(self.x);
22954 __tmp.put_f32_le(self.y);
22955 __tmp.put_f32_le(self.z);
22956 for val in &self.q {
22957 __tmp.put_f32_le(*val);
22958 }
22959 __tmp.put_f32_le(self.vx);
22960 __tmp.put_f32_le(self.vy);
22961 __tmp.put_f32_le(self.vz);
22962 __tmp.put_f32_le(self.rollspeed);
22963 __tmp.put_f32_le(self.pitchspeed);
22964 __tmp.put_f32_le(self.yawspeed);
22965 for val in &self.pose_covariance {
22966 __tmp.put_f32_le(*val);
22967 }
22968 for val in &self.velocity_covariance {
22969 __tmp.put_f32_le(*val);
22970 }
22971 __tmp.put_u8(self.frame_id as u8);
22972 __tmp.put_u8(self.child_frame_id as u8);
22973 if matches!(version, MavlinkVersion::V2) {
22974 __tmp.put_u8(self.reset_counter);
22975 __tmp.put_u8(self.estimator_type as u8);
22976 __tmp.put_i8(self.quality);
22977 let len = __tmp.len();
22978 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22979 } else {
22980 __tmp.len()
22981 }
22982 }
22983}
22984#[doc = "Hardware status sent by an onboard computer."]
22985#[doc = ""]
22986#[doc = "ID: 390"]
22987#[derive(Debug, Clone, PartialEq)]
22988#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22989#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22990#[cfg_attr(feature = "ts", derive(TS))]
22991#[cfg_attr(feature = "ts", ts(export))]
22992pub struct ONBOARD_COMPUTER_STATUS_DATA {
22993 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
22994 pub time_usec: u64,
22995 #[doc = "Time since system boot."]
22996 pub uptime: u32,
22997 #[doc = "Amount of used RAM on the component system. A value of UINT32_MAX implies the field is unused."]
22998 pub ram_usage: u32,
22999 #[doc = "Total amount of RAM on the component system. A value of UINT32_MAX implies the field is unused."]
23000 pub ram_total: u32,
23001 #[doc = "Storage type: 0: HDD, 1: SSD, 2: EMMC, 3: SD card (non-removable), 4: SD card (removable). A value of UINT32_MAX implies the field is unused."]
23002 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23003 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
23004 pub storage_type: [u32; 4],
23005 #[doc = "Amount of used storage space on the component system. A value of UINT32_MAX implies the field is unused."]
23006 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23007 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
23008 pub storage_usage: [u32; 4],
23009 #[doc = "Total amount of storage space on the component system. A value of UINT32_MAX implies the field is unused."]
23010 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23011 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
23012 pub storage_total: [u32; 4],
23013 #[doc = "Link type: 0-9: UART, 10-19: Wired network, 20-29: Wifi, 30-39: Point-to-point proprietary, 40-49: Mesh proprietary"]
23014 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23015 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
23016 pub link_type: [u32; 6],
23017 #[doc = "Network traffic from the component system. A value of UINT32_MAX implies the field is unused."]
23018 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23019 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
23020 pub link_tx_rate: [u32; 6],
23021 #[doc = "Network traffic to the component system. A value of UINT32_MAX implies the field is unused."]
23022 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23023 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
23024 pub link_rx_rate: [u32; 6],
23025 #[doc = "Network capacity from the component system. A value of UINT32_MAX implies the field is unused."]
23026 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23027 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
23028 pub link_tx_max: [u32; 6],
23029 #[doc = "Network capacity to the component system. A value of UINT32_MAX implies the field is unused."]
23030 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23031 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
23032 pub link_rx_max: [u32; 6],
23033 #[doc = "Fan speeds. A value of INT16_MAX implies the field is unused."]
23034 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23035 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
23036 pub fan_speed: [i16; 4],
23037 #[doc = "Type of the onboard computer: 0: Mission computer primary, 1: Mission computer backup 1, 2: Mission computer backup 2, 3: Compute node, 4-5: Compute spares, 6-9: Payload computers."]
23038 pub mavtype: u8,
23039 #[doc = "CPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused."]
23040 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23041 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
23042 pub cpu_cores: [u8; 8],
23043 #[doc = "Combined CPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused."]
23044 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23045 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
23046 pub cpu_combined: [u8; 10],
23047 #[doc = "GPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused."]
23048 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23049 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
23050 pub gpu_cores: [u8; 4],
23051 #[doc = "Combined GPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused."]
23052 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23053 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
23054 pub gpu_combined: [u8; 10],
23055 #[doc = "Temperature of the board. A value of INT8_MAX implies the field is unused."]
23056 pub temperature_board: i8,
23057 #[doc = "Temperature of the CPU core. A value of INT8_MAX implies the field is unused."]
23058 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23059 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
23060 pub temperature_core: [i8; 8],
23061}
23062impl ONBOARD_COMPUTER_STATUS_DATA {
23063 pub const ENCODED_LEN: usize = 238usize;
23064 pub const DEFAULT: Self = Self {
23065 time_usec: 0_u64,
23066 uptime: 0_u32,
23067 ram_usage: 0_u32,
23068 ram_total: 0_u32,
23069 storage_type: [0_u32; 4usize],
23070 storage_usage: [0_u32; 4usize],
23071 storage_total: [0_u32; 4usize],
23072 link_type: [0_u32; 6usize],
23073 link_tx_rate: [0_u32; 6usize],
23074 link_rx_rate: [0_u32; 6usize],
23075 link_tx_max: [0_u32; 6usize],
23076 link_rx_max: [0_u32; 6usize],
23077 fan_speed: [0_i16; 4usize],
23078 mavtype: 0_u8,
23079 cpu_cores: [0_u8; 8usize],
23080 cpu_combined: [0_u8; 10usize],
23081 gpu_cores: [0_u8; 4usize],
23082 gpu_combined: [0_u8; 10usize],
23083 temperature_board: 0_i8,
23084 temperature_core: [0_i8; 8usize],
23085 };
23086 #[cfg(feature = "arbitrary")]
23087 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23088 use arbitrary::{Arbitrary, Unstructured};
23089 let mut buf = [0u8; 1024];
23090 rng.fill_bytes(&mut buf);
23091 let mut unstructured = Unstructured::new(&buf);
23092 Self::arbitrary(&mut unstructured).unwrap_or_default()
23093 }
23094}
23095impl Default for ONBOARD_COMPUTER_STATUS_DATA {
23096 fn default() -> Self {
23097 Self::DEFAULT.clone()
23098 }
23099}
23100impl MessageData for ONBOARD_COMPUTER_STATUS_DATA {
23101 type Message = MavMessage;
23102 const ID: u32 = 390u32;
23103 const NAME: &'static str = "ONBOARD_COMPUTER_STATUS";
23104 const EXTRA_CRC: u8 = 156u8;
23105 const ENCODED_LEN: usize = 238usize;
23106 fn deser(
23107 _version: MavlinkVersion,
23108 __input: &[u8],
23109 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23110 let avail_len = __input.len();
23111 let mut payload_buf = [0; Self::ENCODED_LEN];
23112 let mut buf = if avail_len < Self::ENCODED_LEN {
23113 payload_buf[0..avail_len].copy_from_slice(__input);
23114 Bytes::new(&payload_buf)
23115 } else {
23116 Bytes::new(__input)
23117 };
23118 let mut __struct = Self::default();
23119 __struct.time_usec = buf.get_u64_le()?;
23120 __struct.uptime = buf.get_u32_le()?;
23121 __struct.ram_usage = buf.get_u32_le()?;
23122 __struct.ram_total = buf.get_u32_le()?;
23123 for v in &mut __struct.storage_type {
23124 let val = buf.get_u32_le()?;
23125 *v = val;
23126 }
23127 for v in &mut __struct.storage_usage {
23128 let val = buf.get_u32_le()?;
23129 *v = val;
23130 }
23131 for v in &mut __struct.storage_total {
23132 let val = buf.get_u32_le()?;
23133 *v = val;
23134 }
23135 for v in &mut __struct.link_type {
23136 let val = buf.get_u32_le()?;
23137 *v = val;
23138 }
23139 for v in &mut __struct.link_tx_rate {
23140 let val = buf.get_u32_le()?;
23141 *v = val;
23142 }
23143 for v in &mut __struct.link_rx_rate {
23144 let val = buf.get_u32_le()?;
23145 *v = val;
23146 }
23147 for v in &mut __struct.link_tx_max {
23148 let val = buf.get_u32_le()?;
23149 *v = val;
23150 }
23151 for v in &mut __struct.link_rx_max {
23152 let val = buf.get_u32_le()?;
23153 *v = val;
23154 }
23155 for v in &mut __struct.fan_speed {
23156 let val = buf.get_i16_le()?;
23157 *v = val;
23158 }
23159 __struct.mavtype = buf.get_u8()?;
23160 for v in &mut __struct.cpu_cores {
23161 let val = buf.get_u8()?;
23162 *v = val;
23163 }
23164 for v in &mut __struct.cpu_combined {
23165 let val = buf.get_u8()?;
23166 *v = val;
23167 }
23168 for v in &mut __struct.gpu_cores {
23169 let val = buf.get_u8()?;
23170 *v = val;
23171 }
23172 for v in &mut __struct.gpu_combined {
23173 let val = buf.get_u8()?;
23174 *v = val;
23175 }
23176 __struct.temperature_board = buf.get_i8()?;
23177 for v in &mut __struct.temperature_core {
23178 let val = buf.get_i8()?;
23179 *v = val;
23180 }
23181 Ok(__struct)
23182 }
23183 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23184 let mut __tmp = BytesMut::new(bytes);
23185 #[allow(clippy::absurd_extreme_comparisons)]
23186 #[allow(unused_comparisons)]
23187 if __tmp.remaining() < Self::ENCODED_LEN {
23188 panic!(
23189 "buffer is too small (need {} bytes, but got {})",
23190 Self::ENCODED_LEN,
23191 __tmp.remaining(),
23192 )
23193 }
23194 __tmp.put_u64_le(self.time_usec);
23195 __tmp.put_u32_le(self.uptime);
23196 __tmp.put_u32_le(self.ram_usage);
23197 __tmp.put_u32_le(self.ram_total);
23198 for val in &self.storage_type {
23199 __tmp.put_u32_le(*val);
23200 }
23201 for val in &self.storage_usage {
23202 __tmp.put_u32_le(*val);
23203 }
23204 for val in &self.storage_total {
23205 __tmp.put_u32_le(*val);
23206 }
23207 for val in &self.link_type {
23208 __tmp.put_u32_le(*val);
23209 }
23210 for val in &self.link_tx_rate {
23211 __tmp.put_u32_le(*val);
23212 }
23213 for val in &self.link_rx_rate {
23214 __tmp.put_u32_le(*val);
23215 }
23216 for val in &self.link_tx_max {
23217 __tmp.put_u32_le(*val);
23218 }
23219 for val in &self.link_rx_max {
23220 __tmp.put_u32_le(*val);
23221 }
23222 for val in &self.fan_speed {
23223 __tmp.put_i16_le(*val);
23224 }
23225 __tmp.put_u8(self.mavtype);
23226 for val in &self.cpu_cores {
23227 __tmp.put_u8(*val);
23228 }
23229 for val in &self.cpu_combined {
23230 __tmp.put_u8(*val);
23231 }
23232 for val in &self.gpu_cores {
23233 __tmp.put_u8(*val);
23234 }
23235 for val in &self.gpu_combined {
23236 __tmp.put_u8(*val);
23237 }
23238 __tmp.put_i8(self.temperature_board);
23239 for val in &self.temperature_core {
23240 __tmp.put_i8(*val);
23241 }
23242 if matches!(version, MavlinkVersion::V2) {
23243 let len = __tmp.len();
23244 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23245 } else {
23246 __tmp.len()
23247 }
23248 }
23249}
23250#[doc = "Transmitter (remote ID system) is enabled and ready to start sending location and other required information. This is streamed by transmitter. A flight controller uses it as a condition to arm."]
23251#[doc = ""]
23252#[doc = "ID: 12918"]
23253#[derive(Debug, Clone, PartialEq)]
23254#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23255#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23256#[cfg_attr(feature = "ts", derive(TS))]
23257#[cfg_attr(feature = "ts", ts(export))]
23258pub struct OPEN_DRONE_ID_ARM_STATUS_DATA {
23259 #[doc = "Status level indicating if arming is allowed."]
23260 pub status: MavOdidArmStatus,
23261 #[doc = "Text error message, should be empty if status is good to arm. Fill with nulls in unused portion."]
23262 #[cfg_attr(feature = "ts", ts(type = "string"))]
23263 pub error: CharArray<50>,
23264}
23265impl OPEN_DRONE_ID_ARM_STATUS_DATA {
23266 pub const ENCODED_LEN: usize = 51usize;
23267 pub const DEFAULT: Self = Self {
23268 status: MavOdidArmStatus::DEFAULT,
23269 error: CharArray::new([0_u8; 50usize]),
23270 };
23271 #[cfg(feature = "arbitrary")]
23272 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23273 use arbitrary::{Arbitrary, Unstructured};
23274 let mut buf = [0u8; 1024];
23275 rng.fill_bytes(&mut buf);
23276 let mut unstructured = Unstructured::new(&buf);
23277 Self::arbitrary(&mut unstructured).unwrap_or_default()
23278 }
23279}
23280impl Default for OPEN_DRONE_ID_ARM_STATUS_DATA {
23281 fn default() -> Self {
23282 Self::DEFAULT.clone()
23283 }
23284}
23285impl MessageData for OPEN_DRONE_ID_ARM_STATUS_DATA {
23286 type Message = MavMessage;
23287 const ID: u32 = 12918u32;
23288 const NAME: &'static str = "OPEN_DRONE_ID_ARM_STATUS";
23289 const EXTRA_CRC: u8 = 139u8;
23290 const ENCODED_LEN: usize = 51usize;
23291 fn deser(
23292 _version: MavlinkVersion,
23293 __input: &[u8],
23294 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23295 let avail_len = __input.len();
23296 let mut payload_buf = [0; Self::ENCODED_LEN];
23297 let mut buf = if avail_len < Self::ENCODED_LEN {
23298 payload_buf[0..avail_len].copy_from_slice(__input);
23299 Bytes::new(&payload_buf)
23300 } else {
23301 Bytes::new(__input)
23302 };
23303 let mut __struct = Self::default();
23304 let tmp = buf.get_u8()?;
23305 __struct.status =
23306 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23307 enum_type: "MavOdidArmStatus",
23308 value: tmp as u64,
23309 })?;
23310 let mut tmp = [0_u8; 50usize];
23311 for v in &mut tmp {
23312 *v = buf.get_u8()?;
23313 }
23314 __struct.error = CharArray::new(tmp);
23315 Ok(__struct)
23316 }
23317 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23318 let mut __tmp = BytesMut::new(bytes);
23319 #[allow(clippy::absurd_extreme_comparisons)]
23320 #[allow(unused_comparisons)]
23321 if __tmp.remaining() < Self::ENCODED_LEN {
23322 panic!(
23323 "buffer is too small (need {} bytes, but got {})",
23324 Self::ENCODED_LEN,
23325 __tmp.remaining(),
23326 )
23327 }
23328 __tmp.put_u8(self.status as u8);
23329 for val in &self.error {
23330 __tmp.put_u8(*val);
23331 }
23332 if matches!(version, MavlinkVersion::V2) {
23333 let len = __tmp.len();
23334 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23335 } else {
23336 __tmp.len()
23337 }
23338 }
23339}
23340#[doc = "Data for filling the OpenDroneID Authentication message. The Authentication Message defines a field that can provide a means of authenticity for the identity of the UAS (Unmanned Aircraft System). The Authentication message can have two different formats. For data page 0, the fields PageCount, Length and TimeStamp are present and AuthData is only 17 bytes. For data page 1 through 15, PageCount, Length and TimeStamp are not present and the size of AuthData is 23 bytes."]
23341#[doc = ""]
23342#[doc = "ID: 12902"]
23343#[derive(Debug, Clone, PartialEq)]
23344#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23345#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23346#[cfg_attr(feature = "ts", derive(TS))]
23347#[cfg_attr(feature = "ts", ts(export))]
23348pub struct OPEN_DRONE_ID_AUTHENTICATION_DATA {
23349 #[doc = "This field is only present for page 0. 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019."]
23350 pub timestamp: u32,
23351 #[doc = "System ID (0 for broadcast)."]
23352 pub target_system: u8,
23353 #[doc = "Component ID (0 for broadcast)."]
23354 pub target_component: u8,
23355 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
23356 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23357 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
23358 pub id_or_mac: [u8; 20],
23359 #[doc = "Indicates the type of authentication."]
23360 pub authentication_type: MavOdidAuthType,
23361 #[doc = "Allowed range is 0 - 15."]
23362 pub data_page: u8,
23363 #[doc = "This field is only present for page 0. Allowed range is 0 - 15. See the description of struct ODID_Auth_data at <https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h>."]
23364 pub last_page_index: u8,
23365 #[doc = "This field is only present for page 0. Total bytes of authentication_data from all data pages. See the description of struct ODID_Auth_data at <https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h>."]
23366 pub length: u8,
23367 #[doc = "Opaque authentication data. For page 0, the size is only 17 bytes. For other pages, the size is 23 bytes. Shall be filled with nulls in the unused portion of the field."]
23368 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23369 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
23370 pub authentication_data: [u8; 23],
23371}
23372impl OPEN_DRONE_ID_AUTHENTICATION_DATA {
23373 pub const ENCODED_LEN: usize = 53usize;
23374 pub const DEFAULT: Self = Self {
23375 timestamp: 0_u32,
23376 target_system: 0_u8,
23377 target_component: 0_u8,
23378 id_or_mac: [0_u8; 20usize],
23379 authentication_type: MavOdidAuthType::DEFAULT,
23380 data_page: 0_u8,
23381 last_page_index: 0_u8,
23382 length: 0_u8,
23383 authentication_data: [0_u8; 23usize],
23384 };
23385 #[cfg(feature = "arbitrary")]
23386 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23387 use arbitrary::{Arbitrary, Unstructured};
23388 let mut buf = [0u8; 1024];
23389 rng.fill_bytes(&mut buf);
23390 let mut unstructured = Unstructured::new(&buf);
23391 Self::arbitrary(&mut unstructured).unwrap_or_default()
23392 }
23393}
23394impl Default for OPEN_DRONE_ID_AUTHENTICATION_DATA {
23395 fn default() -> Self {
23396 Self::DEFAULT.clone()
23397 }
23398}
23399impl MessageData for OPEN_DRONE_ID_AUTHENTICATION_DATA {
23400 type Message = MavMessage;
23401 const ID: u32 = 12902u32;
23402 const NAME: &'static str = "OPEN_DRONE_ID_AUTHENTICATION";
23403 const EXTRA_CRC: u8 = 140u8;
23404 const ENCODED_LEN: usize = 53usize;
23405 fn deser(
23406 _version: MavlinkVersion,
23407 __input: &[u8],
23408 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23409 let avail_len = __input.len();
23410 let mut payload_buf = [0; Self::ENCODED_LEN];
23411 let mut buf = if avail_len < Self::ENCODED_LEN {
23412 payload_buf[0..avail_len].copy_from_slice(__input);
23413 Bytes::new(&payload_buf)
23414 } else {
23415 Bytes::new(__input)
23416 };
23417 let mut __struct = Self::default();
23418 __struct.timestamp = buf.get_u32_le()?;
23419 __struct.target_system = buf.get_u8()?;
23420 __struct.target_component = buf.get_u8()?;
23421 for v in &mut __struct.id_or_mac {
23422 let val = buf.get_u8()?;
23423 *v = val;
23424 }
23425 let tmp = buf.get_u8()?;
23426 __struct.authentication_type =
23427 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23428 enum_type: "MavOdidAuthType",
23429 value: tmp as u64,
23430 })?;
23431 __struct.data_page = buf.get_u8()?;
23432 __struct.last_page_index = buf.get_u8()?;
23433 __struct.length = buf.get_u8()?;
23434 for v in &mut __struct.authentication_data {
23435 let val = buf.get_u8()?;
23436 *v = val;
23437 }
23438 Ok(__struct)
23439 }
23440 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23441 let mut __tmp = BytesMut::new(bytes);
23442 #[allow(clippy::absurd_extreme_comparisons)]
23443 #[allow(unused_comparisons)]
23444 if __tmp.remaining() < Self::ENCODED_LEN {
23445 panic!(
23446 "buffer is too small (need {} bytes, but got {})",
23447 Self::ENCODED_LEN,
23448 __tmp.remaining(),
23449 )
23450 }
23451 __tmp.put_u32_le(self.timestamp);
23452 __tmp.put_u8(self.target_system);
23453 __tmp.put_u8(self.target_component);
23454 for val in &self.id_or_mac {
23455 __tmp.put_u8(*val);
23456 }
23457 __tmp.put_u8(self.authentication_type as u8);
23458 __tmp.put_u8(self.data_page);
23459 __tmp.put_u8(self.last_page_index);
23460 __tmp.put_u8(self.length);
23461 for val in &self.authentication_data {
23462 __tmp.put_u8(*val);
23463 }
23464 if matches!(version, MavlinkVersion::V2) {
23465 let len = __tmp.len();
23466 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23467 } else {
23468 __tmp.len()
23469 }
23470 }
23471}
23472#[doc = "Data for filling the OpenDroneID Basic ID message. This and the below messages are primarily meant for feeding data to/from an OpenDroneID implementation. E.g. <https://github.com/opendroneid/opendroneid-core-c>. These messages are compatible with the ASTM F3411 Remote ID standard and the ASD-STAN prEN 4709-002 Direct Remote ID standard. Additional information and usage of these messages is documented at <https://mavlink.io/en/services/opendroneid.html>."]
23473#[doc = ""]
23474#[doc = "ID: 12900"]
23475#[derive(Debug, Clone, PartialEq)]
23476#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23477#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23478#[cfg_attr(feature = "ts", derive(TS))]
23479#[cfg_attr(feature = "ts", ts(export))]
23480pub struct OPEN_DRONE_ID_BASIC_ID_DATA {
23481 #[doc = "System ID (0 for broadcast)."]
23482 pub target_system: u8,
23483 #[doc = "Component ID (0 for broadcast)."]
23484 pub target_component: u8,
23485 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
23486 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23487 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
23488 pub id_or_mac: [u8; 20],
23489 #[doc = "Indicates the format for the uas_id field of this message."]
23490 pub id_type: MavOdidIdType,
23491 #[doc = "Indicates the type of UA (Unmanned Aircraft)."]
23492 pub ua_type: MavOdidUaType,
23493 #[doc = "UAS (Unmanned Aircraft System) ID following the format specified by id_type. Shall be filled with nulls in the unused portion of the field."]
23494 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23495 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
23496 pub uas_id: [u8; 20],
23497}
23498impl OPEN_DRONE_ID_BASIC_ID_DATA {
23499 pub const ENCODED_LEN: usize = 44usize;
23500 pub const DEFAULT: Self = Self {
23501 target_system: 0_u8,
23502 target_component: 0_u8,
23503 id_or_mac: [0_u8; 20usize],
23504 id_type: MavOdidIdType::DEFAULT,
23505 ua_type: MavOdidUaType::DEFAULT,
23506 uas_id: [0_u8; 20usize],
23507 };
23508 #[cfg(feature = "arbitrary")]
23509 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23510 use arbitrary::{Arbitrary, Unstructured};
23511 let mut buf = [0u8; 1024];
23512 rng.fill_bytes(&mut buf);
23513 let mut unstructured = Unstructured::new(&buf);
23514 Self::arbitrary(&mut unstructured).unwrap_or_default()
23515 }
23516}
23517impl Default for OPEN_DRONE_ID_BASIC_ID_DATA {
23518 fn default() -> Self {
23519 Self::DEFAULT.clone()
23520 }
23521}
23522impl MessageData for OPEN_DRONE_ID_BASIC_ID_DATA {
23523 type Message = MavMessage;
23524 const ID: u32 = 12900u32;
23525 const NAME: &'static str = "OPEN_DRONE_ID_BASIC_ID";
23526 const EXTRA_CRC: u8 = 114u8;
23527 const ENCODED_LEN: usize = 44usize;
23528 fn deser(
23529 _version: MavlinkVersion,
23530 __input: &[u8],
23531 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23532 let avail_len = __input.len();
23533 let mut payload_buf = [0; Self::ENCODED_LEN];
23534 let mut buf = if avail_len < Self::ENCODED_LEN {
23535 payload_buf[0..avail_len].copy_from_slice(__input);
23536 Bytes::new(&payload_buf)
23537 } else {
23538 Bytes::new(__input)
23539 };
23540 let mut __struct = Self::default();
23541 __struct.target_system = buf.get_u8()?;
23542 __struct.target_component = buf.get_u8()?;
23543 for v in &mut __struct.id_or_mac {
23544 let val = buf.get_u8()?;
23545 *v = val;
23546 }
23547 let tmp = buf.get_u8()?;
23548 __struct.id_type =
23549 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23550 enum_type: "MavOdidIdType",
23551 value: tmp as u64,
23552 })?;
23553 let tmp = buf.get_u8()?;
23554 __struct.ua_type =
23555 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23556 enum_type: "MavOdidUaType",
23557 value: tmp as u64,
23558 })?;
23559 for v in &mut __struct.uas_id {
23560 let val = buf.get_u8()?;
23561 *v = val;
23562 }
23563 Ok(__struct)
23564 }
23565 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23566 let mut __tmp = BytesMut::new(bytes);
23567 #[allow(clippy::absurd_extreme_comparisons)]
23568 #[allow(unused_comparisons)]
23569 if __tmp.remaining() < Self::ENCODED_LEN {
23570 panic!(
23571 "buffer is too small (need {} bytes, but got {})",
23572 Self::ENCODED_LEN,
23573 __tmp.remaining(),
23574 )
23575 }
23576 __tmp.put_u8(self.target_system);
23577 __tmp.put_u8(self.target_component);
23578 for val in &self.id_or_mac {
23579 __tmp.put_u8(*val);
23580 }
23581 __tmp.put_u8(self.id_type as u8);
23582 __tmp.put_u8(self.ua_type as u8);
23583 for val in &self.uas_id {
23584 __tmp.put_u8(*val);
23585 }
23586 if matches!(version, MavlinkVersion::V2) {
23587 let len = __tmp.len();
23588 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23589 } else {
23590 __tmp.len()
23591 }
23592 }
23593}
23594#[doc = "Data for filling the OpenDroneID Location message. The float data types are 32-bit IEEE 754. The Location message provides the location, altitude, direction and speed of the aircraft."]
23595#[doc = ""]
23596#[doc = "ID: 12901"]
23597#[derive(Debug, Clone, PartialEq)]
23598#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23599#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23600#[cfg_attr(feature = "ts", derive(TS))]
23601#[cfg_attr(feature = "ts", ts(export))]
23602pub struct OPEN_DRONE_ID_LOCATION_DATA {
23603 #[doc = "Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon)."]
23604 pub latitude: i32,
23605 #[doc = "Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon)."]
23606 pub longitude: i32,
23607 #[doc = "The altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m."]
23608 pub altitude_barometric: f32,
23609 #[doc = "The geodetic altitude as defined by WGS84. If unknown: -1000 m."]
23610 pub altitude_geodetic: f32,
23611 #[doc = "The current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference. If unknown: -1000 m."]
23612 pub height: f32,
23613 #[doc = "Seconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000. If unknown: 0xFFFF."]
23614 pub timestamp: f32,
23615 #[doc = "Direction over ground (not heading, but direction of movement) measured clockwise from true North: 0 - 35999 centi-degrees. If unknown: 36100 centi-degrees."]
23616 pub direction: u16,
23617 #[doc = "Ground speed. Positive only. If unknown: 25500 cm/s. If speed is larger than 25425 cm/s, use 25425 cm/s."]
23618 pub speed_horizontal: u16,
23619 #[doc = "The vertical speed. Up is positive. If unknown: 6300 cm/s. If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s."]
23620 pub speed_vertical: i16,
23621 #[doc = "System ID (0 for broadcast)."]
23622 pub target_system: u8,
23623 #[doc = "Component ID (0 for broadcast)."]
23624 pub target_component: u8,
23625 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
23626 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23627 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
23628 pub id_or_mac: [u8; 20],
23629 #[doc = "Indicates whether the unmanned aircraft is on the ground or in the air."]
23630 pub status: MavOdidStatus,
23631 #[doc = "Indicates the reference point for the height field."]
23632 pub height_reference: MavOdidHeightRef,
23633 #[doc = "The accuracy of the horizontal position."]
23634 pub horizontal_accuracy: MavOdidHorAcc,
23635 #[doc = "The accuracy of the vertical position."]
23636 pub vertical_accuracy: MavOdidVerAcc,
23637 #[doc = "The accuracy of the barometric altitude."]
23638 pub barometer_accuracy: MavOdidVerAcc,
23639 #[doc = "The accuracy of the horizontal and vertical speed."]
23640 pub speed_accuracy: MavOdidSpeedAcc,
23641 #[doc = "The accuracy of the timestamps."]
23642 pub timestamp_accuracy: MavOdidTimeAcc,
23643}
23644impl OPEN_DRONE_ID_LOCATION_DATA {
23645 pub const ENCODED_LEN: usize = 59usize;
23646 pub const DEFAULT: Self = Self {
23647 latitude: 0_i32,
23648 longitude: 0_i32,
23649 altitude_barometric: 0.0_f32,
23650 altitude_geodetic: 0.0_f32,
23651 height: 0.0_f32,
23652 timestamp: 0.0_f32,
23653 direction: 0_u16,
23654 speed_horizontal: 0_u16,
23655 speed_vertical: 0_i16,
23656 target_system: 0_u8,
23657 target_component: 0_u8,
23658 id_or_mac: [0_u8; 20usize],
23659 status: MavOdidStatus::DEFAULT,
23660 height_reference: MavOdidHeightRef::DEFAULT,
23661 horizontal_accuracy: MavOdidHorAcc::DEFAULT,
23662 vertical_accuracy: MavOdidVerAcc::DEFAULT,
23663 barometer_accuracy: MavOdidVerAcc::DEFAULT,
23664 speed_accuracy: MavOdidSpeedAcc::DEFAULT,
23665 timestamp_accuracy: MavOdidTimeAcc::DEFAULT,
23666 };
23667 #[cfg(feature = "arbitrary")]
23668 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23669 use arbitrary::{Arbitrary, Unstructured};
23670 let mut buf = [0u8; 1024];
23671 rng.fill_bytes(&mut buf);
23672 let mut unstructured = Unstructured::new(&buf);
23673 Self::arbitrary(&mut unstructured).unwrap_or_default()
23674 }
23675}
23676impl Default for OPEN_DRONE_ID_LOCATION_DATA {
23677 fn default() -> Self {
23678 Self::DEFAULT.clone()
23679 }
23680}
23681impl MessageData for OPEN_DRONE_ID_LOCATION_DATA {
23682 type Message = MavMessage;
23683 const ID: u32 = 12901u32;
23684 const NAME: &'static str = "OPEN_DRONE_ID_LOCATION";
23685 const EXTRA_CRC: u8 = 254u8;
23686 const ENCODED_LEN: usize = 59usize;
23687 fn deser(
23688 _version: MavlinkVersion,
23689 __input: &[u8],
23690 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23691 let avail_len = __input.len();
23692 let mut payload_buf = [0; Self::ENCODED_LEN];
23693 let mut buf = if avail_len < Self::ENCODED_LEN {
23694 payload_buf[0..avail_len].copy_from_slice(__input);
23695 Bytes::new(&payload_buf)
23696 } else {
23697 Bytes::new(__input)
23698 };
23699 let mut __struct = Self::default();
23700 __struct.latitude = buf.get_i32_le()?;
23701 __struct.longitude = buf.get_i32_le()?;
23702 __struct.altitude_barometric = buf.get_f32_le()?;
23703 __struct.altitude_geodetic = buf.get_f32_le()?;
23704 __struct.height = buf.get_f32_le()?;
23705 __struct.timestamp = buf.get_f32_le()?;
23706 __struct.direction = buf.get_u16_le()?;
23707 __struct.speed_horizontal = buf.get_u16_le()?;
23708 __struct.speed_vertical = buf.get_i16_le()?;
23709 __struct.target_system = buf.get_u8()?;
23710 __struct.target_component = buf.get_u8()?;
23711 for v in &mut __struct.id_or_mac {
23712 let val = buf.get_u8()?;
23713 *v = val;
23714 }
23715 let tmp = buf.get_u8()?;
23716 __struct.status =
23717 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23718 enum_type: "MavOdidStatus",
23719 value: tmp as u64,
23720 })?;
23721 let tmp = buf.get_u8()?;
23722 __struct.height_reference =
23723 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23724 enum_type: "MavOdidHeightRef",
23725 value: tmp as u64,
23726 })?;
23727 let tmp = buf.get_u8()?;
23728 __struct.horizontal_accuracy =
23729 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23730 enum_type: "MavOdidHorAcc",
23731 value: tmp as u64,
23732 })?;
23733 let tmp = buf.get_u8()?;
23734 __struct.vertical_accuracy =
23735 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23736 enum_type: "MavOdidVerAcc",
23737 value: tmp as u64,
23738 })?;
23739 let tmp = buf.get_u8()?;
23740 __struct.barometer_accuracy =
23741 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23742 enum_type: "MavOdidVerAcc",
23743 value: tmp as u64,
23744 })?;
23745 let tmp = buf.get_u8()?;
23746 __struct.speed_accuracy =
23747 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23748 enum_type: "MavOdidSpeedAcc",
23749 value: tmp as u64,
23750 })?;
23751 let tmp = buf.get_u8()?;
23752 __struct.timestamp_accuracy =
23753 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23754 enum_type: "MavOdidTimeAcc",
23755 value: tmp as u64,
23756 })?;
23757 Ok(__struct)
23758 }
23759 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23760 let mut __tmp = BytesMut::new(bytes);
23761 #[allow(clippy::absurd_extreme_comparisons)]
23762 #[allow(unused_comparisons)]
23763 if __tmp.remaining() < Self::ENCODED_LEN {
23764 panic!(
23765 "buffer is too small (need {} bytes, but got {})",
23766 Self::ENCODED_LEN,
23767 __tmp.remaining(),
23768 )
23769 }
23770 __tmp.put_i32_le(self.latitude);
23771 __tmp.put_i32_le(self.longitude);
23772 __tmp.put_f32_le(self.altitude_barometric);
23773 __tmp.put_f32_le(self.altitude_geodetic);
23774 __tmp.put_f32_le(self.height);
23775 __tmp.put_f32_le(self.timestamp);
23776 __tmp.put_u16_le(self.direction);
23777 __tmp.put_u16_le(self.speed_horizontal);
23778 __tmp.put_i16_le(self.speed_vertical);
23779 __tmp.put_u8(self.target_system);
23780 __tmp.put_u8(self.target_component);
23781 for val in &self.id_or_mac {
23782 __tmp.put_u8(*val);
23783 }
23784 __tmp.put_u8(self.status as u8);
23785 __tmp.put_u8(self.height_reference as u8);
23786 __tmp.put_u8(self.horizontal_accuracy as u8);
23787 __tmp.put_u8(self.vertical_accuracy as u8);
23788 __tmp.put_u8(self.barometer_accuracy as u8);
23789 __tmp.put_u8(self.speed_accuracy as u8);
23790 __tmp.put_u8(self.timestamp_accuracy as u8);
23791 if matches!(version, MavlinkVersion::V2) {
23792 let len = __tmp.len();
23793 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23794 } else {
23795 __tmp.len()
23796 }
23797 }
23798}
23799#[doc = "An OpenDroneID message pack is a container for multiple encoded OpenDroneID messages (i.e. not in the format given for the above message descriptions but after encoding into the compressed OpenDroneID byte format). Used e.g. when transmitting on Bluetooth 5.0 Long Range/Extended Advertising or on WiFi Neighbor Aware Networking or on WiFi Beacon."]
23800#[doc = ""]
23801#[doc = "ID: 12915"]
23802#[derive(Debug, Clone, PartialEq)]
23803#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23804#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23805#[cfg_attr(feature = "ts", derive(TS))]
23806#[cfg_attr(feature = "ts", ts(export))]
23807pub struct OPEN_DRONE_ID_MESSAGE_PACK_DATA {
23808 #[doc = "System ID (0 for broadcast)."]
23809 pub target_system: u8,
23810 #[doc = "Component ID (0 for broadcast)."]
23811 pub target_component: u8,
23812 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
23813 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23814 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
23815 pub id_or_mac: [u8; 20],
23816 #[doc = "This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specified to have this length."]
23817 pub single_message_size: u8,
23818 #[doc = "Number of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 9."]
23819 pub msg_pack_size: u8,
23820 #[doc = "Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field."]
23821 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23822 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
23823 pub messages: [u8; 225],
23824}
23825impl OPEN_DRONE_ID_MESSAGE_PACK_DATA {
23826 pub const ENCODED_LEN: usize = 249usize;
23827 pub const DEFAULT: Self = Self {
23828 target_system: 0_u8,
23829 target_component: 0_u8,
23830 id_or_mac: [0_u8; 20usize],
23831 single_message_size: 0_u8,
23832 msg_pack_size: 0_u8,
23833 messages: [0_u8; 225usize],
23834 };
23835 #[cfg(feature = "arbitrary")]
23836 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23837 use arbitrary::{Arbitrary, Unstructured};
23838 let mut buf = [0u8; 1024];
23839 rng.fill_bytes(&mut buf);
23840 let mut unstructured = Unstructured::new(&buf);
23841 Self::arbitrary(&mut unstructured).unwrap_or_default()
23842 }
23843}
23844impl Default for OPEN_DRONE_ID_MESSAGE_PACK_DATA {
23845 fn default() -> Self {
23846 Self::DEFAULT.clone()
23847 }
23848}
23849impl MessageData for OPEN_DRONE_ID_MESSAGE_PACK_DATA {
23850 type Message = MavMessage;
23851 const ID: u32 = 12915u32;
23852 const NAME: &'static str = "OPEN_DRONE_ID_MESSAGE_PACK";
23853 const EXTRA_CRC: u8 = 94u8;
23854 const ENCODED_LEN: usize = 249usize;
23855 fn deser(
23856 _version: MavlinkVersion,
23857 __input: &[u8],
23858 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23859 let avail_len = __input.len();
23860 let mut payload_buf = [0; Self::ENCODED_LEN];
23861 let mut buf = if avail_len < Self::ENCODED_LEN {
23862 payload_buf[0..avail_len].copy_from_slice(__input);
23863 Bytes::new(&payload_buf)
23864 } else {
23865 Bytes::new(__input)
23866 };
23867 let mut __struct = Self::default();
23868 __struct.target_system = buf.get_u8()?;
23869 __struct.target_component = buf.get_u8()?;
23870 for v in &mut __struct.id_or_mac {
23871 let val = buf.get_u8()?;
23872 *v = val;
23873 }
23874 __struct.single_message_size = buf.get_u8()?;
23875 __struct.msg_pack_size = buf.get_u8()?;
23876 for v in &mut __struct.messages {
23877 let val = buf.get_u8()?;
23878 *v = val;
23879 }
23880 Ok(__struct)
23881 }
23882 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23883 let mut __tmp = BytesMut::new(bytes);
23884 #[allow(clippy::absurd_extreme_comparisons)]
23885 #[allow(unused_comparisons)]
23886 if __tmp.remaining() < Self::ENCODED_LEN {
23887 panic!(
23888 "buffer is too small (need {} bytes, but got {})",
23889 Self::ENCODED_LEN,
23890 __tmp.remaining(),
23891 )
23892 }
23893 __tmp.put_u8(self.target_system);
23894 __tmp.put_u8(self.target_component);
23895 for val in &self.id_or_mac {
23896 __tmp.put_u8(*val);
23897 }
23898 __tmp.put_u8(self.single_message_size);
23899 __tmp.put_u8(self.msg_pack_size);
23900 for val in &self.messages {
23901 __tmp.put_u8(*val);
23902 }
23903 if matches!(version, MavlinkVersion::V2) {
23904 let len = __tmp.len();
23905 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23906 } else {
23907 __tmp.len()
23908 }
23909 }
23910}
23911#[doc = "Data for filling the OpenDroneID Operator ID message, which contains the CAA (Civil Aviation Authority) issued operator ID."]
23912#[doc = ""]
23913#[doc = "ID: 12905"]
23914#[derive(Debug, Clone, PartialEq)]
23915#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23916#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23917#[cfg_attr(feature = "ts", derive(TS))]
23918#[cfg_attr(feature = "ts", ts(export))]
23919pub struct OPEN_DRONE_ID_OPERATOR_ID_DATA {
23920 #[doc = "System ID (0 for broadcast)."]
23921 pub target_system: u8,
23922 #[doc = "Component ID (0 for broadcast)."]
23923 pub target_component: u8,
23924 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
23925 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23926 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
23927 pub id_or_mac: [u8; 20],
23928 #[doc = "Indicates the type of the operator_id field."]
23929 pub operator_id_type: MavOdidOperatorIdType,
23930 #[doc = "Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field."]
23931 #[cfg_attr(feature = "ts", ts(type = "string"))]
23932 pub operator_id: CharArray<20>,
23933}
23934impl OPEN_DRONE_ID_OPERATOR_ID_DATA {
23935 pub const ENCODED_LEN: usize = 43usize;
23936 pub const DEFAULT: Self = Self {
23937 target_system: 0_u8,
23938 target_component: 0_u8,
23939 id_or_mac: [0_u8; 20usize],
23940 operator_id_type: MavOdidOperatorIdType::DEFAULT,
23941 operator_id: CharArray::new([0_u8; 20usize]),
23942 };
23943 #[cfg(feature = "arbitrary")]
23944 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23945 use arbitrary::{Arbitrary, Unstructured};
23946 let mut buf = [0u8; 1024];
23947 rng.fill_bytes(&mut buf);
23948 let mut unstructured = Unstructured::new(&buf);
23949 Self::arbitrary(&mut unstructured).unwrap_or_default()
23950 }
23951}
23952impl Default for OPEN_DRONE_ID_OPERATOR_ID_DATA {
23953 fn default() -> Self {
23954 Self::DEFAULT.clone()
23955 }
23956}
23957impl MessageData for OPEN_DRONE_ID_OPERATOR_ID_DATA {
23958 type Message = MavMessage;
23959 const ID: u32 = 12905u32;
23960 const NAME: &'static str = "OPEN_DRONE_ID_OPERATOR_ID";
23961 const EXTRA_CRC: u8 = 49u8;
23962 const ENCODED_LEN: usize = 43usize;
23963 fn deser(
23964 _version: MavlinkVersion,
23965 __input: &[u8],
23966 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23967 let avail_len = __input.len();
23968 let mut payload_buf = [0; Self::ENCODED_LEN];
23969 let mut buf = if avail_len < Self::ENCODED_LEN {
23970 payload_buf[0..avail_len].copy_from_slice(__input);
23971 Bytes::new(&payload_buf)
23972 } else {
23973 Bytes::new(__input)
23974 };
23975 let mut __struct = Self::default();
23976 __struct.target_system = buf.get_u8()?;
23977 __struct.target_component = buf.get_u8()?;
23978 for v in &mut __struct.id_or_mac {
23979 let val = buf.get_u8()?;
23980 *v = val;
23981 }
23982 let tmp = buf.get_u8()?;
23983 __struct.operator_id_type =
23984 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23985 enum_type: "MavOdidOperatorIdType",
23986 value: tmp as u64,
23987 })?;
23988 let mut tmp = [0_u8; 20usize];
23989 for v in &mut tmp {
23990 *v = buf.get_u8()?;
23991 }
23992 __struct.operator_id = CharArray::new(tmp);
23993 Ok(__struct)
23994 }
23995 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23996 let mut __tmp = BytesMut::new(bytes);
23997 #[allow(clippy::absurd_extreme_comparisons)]
23998 #[allow(unused_comparisons)]
23999 if __tmp.remaining() < Self::ENCODED_LEN {
24000 panic!(
24001 "buffer is too small (need {} bytes, but got {})",
24002 Self::ENCODED_LEN,
24003 __tmp.remaining(),
24004 )
24005 }
24006 __tmp.put_u8(self.target_system);
24007 __tmp.put_u8(self.target_component);
24008 for val in &self.id_or_mac {
24009 __tmp.put_u8(*val);
24010 }
24011 __tmp.put_u8(self.operator_id_type as u8);
24012 for val in &self.operator_id {
24013 __tmp.put_u8(*val);
24014 }
24015 if matches!(version, MavlinkVersion::V2) {
24016 let len = __tmp.len();
24017 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24018 } else {
24019 __tmp.len()
24020 }
24021 }
24022}
24023#[doc = "Data for filling the OpenDroneID Self ID message. The Self ID Message is an opportunity for the operator to (optionally) declare their identity and purpose of the flight. This message can provide additional information that could reduce the threat profile of a UA (Unmanned Aircraft) flying in a particular area or manner. This message can also be used to provide optional additional clarification in an emergency/remote ID system failure situation."]
24024#[doc = ""]
24025#[doc = "ID: 12903"]
24026#[derive(Debug, Clone, PartialEq)]
24027#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24028#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24029#[cfg_attr(feature = "ts", derive(TS))]
24030#[cfg_attr(feature = "ts", ts(export))]
24031pub struct OPEN_DRONE_ID_SELF_ID_DATA {
24032 #[doc = "System ID (0 for broadcast)."]
24033 pub target_system: u8,
24034 #[doc = "Component ID (0 for broadcast)."]
24035 pub target_component: u8,
24036 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
24037 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24038 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
24039 pub id_or_mac: [u8; 20],
24040 #[doc = "Indicates the type of the description field."]
24041 pub description_type: MavOdidDescType,
24042 #[doc = "Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field."]
24043 #[cfg_attr(feature = "ts", ts(type = "string"))]
24044 pub description: CharArray<23>,
24045}
24046impl OPEN_DRONE_ID_SELF_ID_DATA {
24047 pub const ENCODED_LEN: usize = 46usize;
24048 pub const DEFAULT: Self = Self {
24049 target_system: 0_u8,
24050 target_component: 0_u8,
24051 id_or_mac: [0_u8; 20usize],
24052 description_type: MavOdidDescType::DEFAULT,
24053 description: CharArray::new([0_u8; 23usize]),
24054 };
24055 #[cfg(feature = "arbitrary")]
24056 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24057 use arbitrary::{Arbitrary, Unstructured};
24058 let mut buf = [0u8; 1024];
24059 rng.fill_bytes(&mut buf);
24060 let mut unstructured = Unstructured::new(&buf);
24061 Self::arbitrary(&mut unstructured).unwrap_or_default()
24062 }
24063}
24064impl Default for OPEN_DRONE_ID_SELF_ID_DATA {
24065 fn default() -> Self {
24066 Self::DEFAULT.clone()
24067 }
24068}
24069impl MessageData for OPEN_DRONE_ID_SELF_ID_DATA {
24070 type Message = MavMessage;
24071 const ID: u32 = 12903u32;
24072 const NAME: &'static str = "OPEN_DRONE_ID_SELF_ID";
24073 const EXTRA_CRC: u8 = 249u8;
24074 const ENCODED_LEN: usize = 46usize;
24075 fn deser(
24076 _version: MavlinkVersion,
24077 __input: &[u8],
24078 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24079 let avail_len = __input.len();
24080 let mut payload_buf = [0; Self::ENCODED_LEN];
24081 let mut buf = if avail_len < Self::ENCODED_LEN {
24082 payload_buf[0..avail_len].copy_from_slice(__input);
24083 Bytes::new(&payload_buf)
24084 } else {
24085 Bytes::new(__input)
24086 };
24087 let mut __struct = Self::default();
24088 __struct.target_system = buf.get_u8()?;
24089 __struct.target_component = buf.get_u8()?;
24090 for v in &mut __struct.id_or_mac {
24091 let val = buf.get_u8()?;
24092 *v = val;
24093 }
24094 let tmp = buf.get_u8()?;
24095 __struct.description_type =
24096 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
24097 enum_type: "MavOdidDescType",
24098 value: tmp as u64,
24099 })?;
24100 let mut tmp = [0_u8; 23usize];
24101 for v in &mut tmp {
24102 *v = buf.get_u8()?;
24103 }
24104 __struct.description = CharArray::new(tmp);
24105 Ok(__struct)
24106 }
24107 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24108 let mut __tmp = BytesMut::new(bytes);
24109 #[allow(clippy::absurd_extreme_comparisons)]
24110 #[allow(unused_comparisons)]
24111 if __tmp.remaining() < Self::ENCODED_LEN {
24112 panic!(
24113 "buffer is too small (need {} bytes, but got {})",
24114 Self::ENCODED_LEN,
24115 __tmp.remaining(),
24116 )
24117 }
24118 __tmp.put_u8(self.target_system);
24119 __tmp.put_u8(self.target_component);
24120 for val in &self.id_or_mac {
24121 __tmp.put_u8(*val);
24122 }
24123 __tmp.put_u8(self.description_type as u8);
24124 for val in &self.description {
24125 __tmp.put_u8(*val);
24126 }
24127 if matches!(version, MavlinkVersion::V2) {
24128 let len = __tmp.len();
24129 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24130 } else {
24131 __tmp.len()
24132 }
24133 }
24134}
24135#[doc = "Data for filling the OpenDroneID System message. The System Message contains general system information including the operator location/altitude and possible aircraft group and/or category/class information."]
24136#[doc = ""]
24137#[doc = "ID: 12904"]
24138#[derive(Debug, Clone, PartialEq)]
24139#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24140#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24141#[cfg_attr(feature = "ts", derive(TS))]
24142#[cfg_attr(feature = "ts", ts(export))]
24143pub struct OPEN_DRONE_ID_SYSTEM_DATA {
24144 #[doc = "Latitude of the operator. If unknown: 0 (both Lat/Lon)."]
24145 pub operator_latitude: i32,
24146 #[doc = "Longitude of the operator. If unknown: 0 (both Lat/Lon)."]
24147 pub operator_longitude: i32,
24148 #[doc = "Area Operations Ceiling relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA."]
24149 pub area_ceiling: f32,
24150 #[doc = "Area Operations Floor relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA."]
24151 pub area_floor: f32,
24152 #[doc = "Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m."]
24153 pub operator_altitude_geo: f32,
24154 #[doc = "32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019."]
24155 pub timestamp: u32,
24156 #[doc = "Number of aircraft in the area, group or formation (default 1). Used only for swarms/multiple UA."]
24157 pub area_count: u16,
24158 #[doc = "Radius of the cylindrical area of the group or formation (default 0). Used only for swarms/multiple UA."]
24159 pub area_radius: u16,
24160 #[doc = "System ID (0 for broadcast)."]
24161 pub target_system: u8,
24162 #[doc = "Component ID (0 for broadcast)."]
24163 pub target_component: u8,
24164 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
24165 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24166 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
24167 pub id_or_mac: [u8; 20],
24168 #[doc = "Specifies the operator location type."]
24169 pub operator_location_type: MavOdidOperatorLocationType,
24170 #[doc = "Specifies the classification type of the UA."]
24171 pub classification_type: MavOdidClassificationType,
24172 #[doc = "When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA."]
24173 pub category_eu: MavOdidCategoryEu,
24174 #[doc = "When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA."]
24175 pub class_eu: MavOdidClassEu,
24176}
24177impl OPEN_DRONE_ID_SYSTEM_DATA {
24178 pub const ENCODED_LEN: usize = 54usize;
24179 pub const DEFAULT: Self = Self {
24180 operator_latitude: 0_i32,
24181 operator_longitude: 0_i32,
24182 area_ceiling: 0.0_f32,
24183 area_floor: 0.0_f32,
24184 operator_altitude_geo: 0.0_f32,
24185 timestamp: 0_u32,
24186 area_count: 0_u16,
24187 area_radius: 0_u16,
24188 target_system: 0_u8,
24189 target_component: 0_u8,
24190 id_or_mac: [0_u8; 20usize],
24191 operator_location_type: MavOdidOperatorLocationType::DEFAULT,
24192 classification_type: MavOdidClassificationType::DEFAULT,
24193 category_eu: MavOdidCategoryEu::DEFAULT,
24194 class_eu: MavOdidClassEu::DEFAULT,
24195 };
24196 #[cfg(feature = "arbitrary")]
24197 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24198 use arbitrary::{Arbitrary, Unstructured};
24199 let mut buf = [0u8; 1024];
24200 rng.fill_bytes(&mut buf);
24201 let mut unstructured = Unstructured::new(&buf);
24202 Self::arbitrary(&mut unstructured).unwrap_or_default()
24203 }
24204}
24205impl Default for OPEN_DRONE_ID_SYSTEM_DATA {
24206 fn default() -> Self {
24207 Self::DEFAULT.clone()
24208 }
24209}
24210impl MessageData for OPEN_DRONE_ID_SYSTEM_DATA {
24211 type Message = MavMessage;
24212 const ID: u32 = 12904u32;
24213 const NAME: &'static str = "OPEN_DRONE_ID_SYSTEM";
24214 const EXTRA_CRC: u8 = 77u8;
24215 const ENCODED_LEN: usize = 54usize;
24216 fn deser(
24217 _version: MavlinkVersion,
24218 __input: &[u8],
24219 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24220 let avail_len = __input.len();
24221 let mut payload_buf = [0; Self::ENCODED_LEN];
24222 let mut buf = if avail_len < Self::ENCODED_LEN {
24223 payload_buf[0..avail_len].copy_from_slice(__input);
24224 Bytes::new(&payload_buf)
24225 } else {
24226 Bytes::new(__input)
24227 };
24228 let mut __struct = Self::default();
24229 __struct.operator_latitude = buf.get_i32_le()?;
24230 __struct.operator_longitude = buf.get_i32_le()?;
24231 __struct.area_ceiling = buf.get_f32_le()?;
24232 __struct.area_floor = buf.get_f32_le()?;
24233 __struct.operator_altitude_geo = buf.get_f32_le()?;
24234 __struct.timestamp = buf.get_u32_le()?;
24235 __struct.area_count = buf.get_u16_le()?;
24236 __struct.area_radius = buf.get_u16_le()?;
24237 __struct.target_system = buf.get_u8()?;
24238 __struct.target_component = buf.get_u8()?;
24239 for v in &mut __struct.id_or_mac {
24240 let val = buf.get_u8()?;
24241 *v = val;
24242 }
24243 let tmp = buf.get_u8()?;
24244 __struct.operator_location_type =
24245 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
24246 enum_type: "MavOdidOperatorLocationType",
24247 value: tmp as u64,
24248 })?;
24249 let tmp = buf.get_u8()?;
24250 __struct.classification_type =
24251 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
24252 enum_type: "MavOdidClassificationType",
24253 value: tmp as u64,
24254 })?;
24255 let tmp = buf.get_u8()?;
24256 __struct.category_eu =
24257 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
24258 enum_type: "MavOdidCategoryEu",
24259 value: tmp as u64,
24260 })?;
24261 let tmp = buf.get_u8()?;
24262 __struct.class_eu =
24263 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
24264 enum_type: "MavOdidClassEu",
24265 value: tmp as u64,
24266 })?;
24267 Ok(__struct)
24268 }
24269 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24270 let mut __tmp = BytesMut::new(bytes);
24271 #[allow(clippy::absurd_extreme_comparisons)]
24272 #[allow(unused_comparisons)]
24273 if __tmp.remaining() < Self::ENCODED_LEN {
24274 panic!(
24275 "buffer is too small (need {} bytes, but got {})",
24276 Self::ENCODED_LEN,
24277 __tmp.remaining(),
24278 )
24279 }
24280 __tmp.put_i32_le(self.operator_latitude);
24281 __tmp.put_i32_le(self.operator_longitude);
24282 __tmp.put_f32_le(self.area_ceiling);
24283 __tmp.put_f32_le(self.area_floor);
24284 __tmp.put_f32_le(self.operator_altitude_geo);
24285 __tmp.put_u32_le(self.timestamp);
24286 __tmp.put_u16_le(self.area_count);
24287 __tmp.put_u16_le(self.area_radius);
24288 __tmp.put_u8(self.target_system);
24289 __tmp.put_u8(self.target_component);
24290 for val in &self.id_or_mac {
24291 __tmp.put_u8(*val);
24292 }
24293 __tmp.put_u8(self.operator_location_type as u8);
24294 __tmp.put_u8(self.classification_type as u8);
24295 __tmp.put_u8(self.category_eu as u8);
24296 __tmp.put_u8(self.class_eu as u8);
24297 if matches!(version, MavlinkVersion::V2) {
24298 let len = __tmp.len();
24299 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24300 } else {
24301 __tmp.len()
24302 }
24303 }
24304}
24305#[doc = "Update the data in the OPEN_DRONE_ID_SYSTEM message with new location information. This can be sent to update the location information for the operator when no other information in the SYSTEM message has changed. This message allows for efficient operation on radio links which have limited uplink bandwidth while meeting requirements for update frequency of the operator location."]
24306#[doc = ""]
24307#[doc = "ID: 12919"]
24308#[derive(Debug, Clone, PartialEq)]
24309#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24310#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24311#[cfg_attr(feature = "ts", derive(TS))]
24312#[cfg_attr(feature = "ts", ts(export))]
24313pub struct OPEN_DRONE_ID_SYSTEM_UPDATE_DATA {
24314 #[doc = "Latitude of the operator. If unknown: 0 (both Lat/Lon)."]
24315 pub operator_latitude: i32,
24316 #[doc = "Longitude of the operator. If unknown: 0 (both Lat/Lon)."]
24317 pub operator_longitude: i32,
24318 #[doc = "Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m."]
24319 pub operator_altitude_geo: f32,
24320 #[doc = "32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019."]
24321 pub timestamp: u32,
24322 #[doc = "System ID (0 for broadcast)."]
24323 pub target_system: u8,
24324 #[doc = "Component ID (0 for broadcast)."]
24325 pub target_component: u8,
24326}
24327impl OPEN_DRONE_ID_SYSTEM_UPDATE_DATA {
24328 pub const ENCODED_LEN: usize = 18usize;
24329 pub const DEFAULT: Self = Self {
24330 operator_latitude: 0_i32,
24331 operator_longitude: 0_i32,
24332 operator_altitude_geo: 0.0_f32,
24333 timestamp: 0_u32,
24334 target_system: 0_u8,
24335 target_component: 0_u8,
24336 };
24337 #[cfg(feature = "arbitrary")]
24338 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24339 use arbitrary::{Arbitrary, Unstructured};
24340 let mut buf = [0u8; 1024];
24341 rng.fill_bytes(&mut buf);
24342 let mut unstructured = Unstructured::new(&buf);
24343 Self::arbitrary(&mut unstructured).unwrap_or_default()
24344 }
24345}
24346impl Default for OPEN_DRONE_ID_SYSTEM_UPDATE_DATA {
24347 fn default() -> Self {
24348 Self::DEFAULT.clone()
24349 }
24350}
24351impl MessageData for OPEN_DRONE_ID_SYSTEM_UPDATE_DATA {
24352 type Message = MavMessage;
24353 const ID: u32 = 12919u32;
24354 const NAME: &'static str = "OPEN_DRONE_ID_SYSTEM_UPDATE";
24355 const EXTRA_CRC: u8 = 7u8;
24356 const ENCODED_LEN: usize = 18usize;
24357 fn deser(
24358 _version: MavlinkVersion,
24359 __input: &[u8],
24360 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24361 let avail_len = __input.len();
24362 let mut payload_buf = [0; Self::ENCODED_LEN];
24363 let mut buf = if avail_len < Self::ENCODED_LEN {
24364 payload_buf[0..avail_len].copy_from_slice(__input);
24365 Bytes::new(&payload_buf)
24366 } else {
24367 Bytes::new(__input)
24368 };
24369 let mut __struct = Self::default();
24370 __struct.operator_latitude = buf.get_i32_le()?;
24371 __struct.operator_longitude = buf.get_i32_le()?;
24372 __struct.operator_altitude_geo = buf.get_f32_le()?;
24373 __struct.timestamp = buf.get_u32_le()?;
24374 __struct.target_system = buf.get_u8()?;
24375 __struct.target_component = buf.get_u8()?;
24376 Ok(__struct)
24377 }
24378 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24379 let mut __tmp = BytesMut::new(bytes);
24380 #[allow(clippy::absurd_extreme_comparisons)]
24381 #[allow(unused_comparisons)]
24382 if __tmp.remaining() < Self::ENCODED_LEN {
24383 panic!(
24384 "buffer is too small (need {} bytes, but got {})",
24385 Self::ENCODED_LEN,
24386 __tmp.remaining(),
24387 )
24388 }
24389 __tmp.put_i32_le(self.operator_latitude);
24390 __tmp.put_i32_le(self.operator_longitude);
24391 __tmp.put_f32_le(self.operator_altitude_geo);
24392 __tmp.put_u32_le(self.timestamp);
24393 __tmp.put_u8(self.target_system);
24394 __tmp.put_u8(self.target_component);
24395 if matches!(version, MavlinkVersion::V2) {
24396 let len = __tmp.len();
24397 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24398 } else {
24399 __tmp.len()
24400 }
24401 }
24402}
24403#[doc = "Optical flow from a flow sensor (e.g. optical mouse sensor)."]
24404#[doc = ""]
24405#[doc = "ID: 100"]
24406#[derive(Debug, Clone, PartialEq)]
24407#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24408#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24409#[cfg_attr(feature = "ts", derive(TS))]
24410#[cfg_attr(feature = "ts", ts(export))]
24411pub struct OPTICAL_FLOW_DATA {
24412 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
24413 pub time_usec: u64,
24414 #[doc = "Flow in x-sensor direction, angular-speed compensated"]
24415 pub flow_comp_m_x: f32,
24416 #[doc = "Flow in y-sensor direction, angular-speed compensated"]
24417 pub flow_comp_m_y: f32,
24418 #[doc = "Ground distance. Positive value: distance known. Negative value: Unknown distance"]
24419 pub ground_distance: f32,
24420 #[doc = "Flow in x-sensor direction"]
24421 pub flow_x: i16,
24422 #[doc = "Flow in y-sensor direction"]
24423 pub flow_y: i16,
24424 #[doc = "Sensor ID"]
24425 pub sensor_id: u8,
24426 #[doc = "Optical flow quality / confidence. 0: bad, 255: maximum quality"]
24427 pub quality: u8,
24428 #[doc = "Flow rate about X axis"]
24429 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24430 pub flow_rate_x: f32,
24431 #[doc = "Flow rate about Y axis"]
24432 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24433 pub flow_rate_y: f32,
24434}
24435impl OPTICAL_FLOW_DATA {
24436 pub const ENCODED_LEN: usize = 34usize;
24437 pub const DEFAULT: Self = Self {
24438 time_usec: 0_u64,
24439 flow_comp_m_x: 0.0_f32,
24440 flow_comp_m_y: 0.0_f32,
24441 ground_distance: 0.0_f32,
24442 flow_x: 0_i16,
24443 flow_y: 0_i16,
24444 sensor_id: 0_u8,
24445 quality: 0_u8,
24446 flow_rate_x: 0.0_f32,
24447 flow_rate_y: 0.0_f32,
24448 };
24449 #[cfg(feature = "arbitrary")]
24450 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24451 use arbitrary::{Arbitrary, Unstructured};
24452 let mut buf = [0u8; 1024];
24453 rng.fill_bytes(&mut buf);
24454 let mut unstructured = Unstructured::new(&buf);
24455 Self::arbitrary(&mut unstructured).unwrap_or_default()
24456 }
24457}
24458impl Default for OPTICAL_FLOW_DATA {
24459 fn default() -> Self {
24460 Self::DEFAULT.clone()
24461 }
24462}
24463impl MessageData for OPTICAL_FLOW_DATA {
24464 type Message = MavMessage;
24465 const ID: u32 = 100u32;
24466 const NAME: &'static str = "OPTICAL_FLOW";
24467 const EXTRA_CRC: u8 = 175u8;
24468 const ENCODED_LEN: usize = 34usize;
24469 fn deser(
24470 _version: MavlinkVersion,
24471 __input: &[u8],
24472 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24473 let avail_len = __input.len();
24474 let mut payload_buf = [0; Self::ENCODED_LEN];
24475 let mut buf = if avail_len < Self::ENCODED_LEN {
24476 payload_buf[0..avail_len].copy_from_slice(__input);
24477 Bytes::new(&payload_buf)
24478 } else {
24479 Bytes::new(__input)
24480 };
24481 let mut __struct = Self::default();
24482 __struct.time_usec = buf.get_u64_le()?;
24483 __struct.flow_comp_m_x = buf.get_f32_le()?;
24484 __struct.flow_comp_m_y = buf.get_f32_le()?;
24485 __struct.ground_distance = buf.get_f32_le()?;
24486 __struct.flow_x = buf.get_i16_le()?;
24487 __struct.flow_y = buf.get_i16_le()?;
24488 __struct.sensor_id = buf.get_u8()?;
24489 __struct.quality = buf.get_u8()?;
24490 __struct.flow_rate_x = buf.get_f32_le()?;
24491 __struct.flow_rate_y = buf.get_f32_le()?;
24492 Ok(__struct)
24493 }
24494 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24495 let mut __tmp = BytesMut::new(bytes);
24496 #[allow(clippy::absurd_extreme_comparisons)]
24497 #[allow(unused_comparisons)]
24498 if __tmp.remaining() < Self::ENCODED_LEN {
24499 panic!(
24500 "buffer is too small (need {} bytes, but got {})",
24501 Self::ENCODED_LEN,
24502 __tmp.remaining(),
24503 )
24504 }
24505 __tmp.put_u64_le(self.time_usec);
24506 __tmp.put_f32_le(self.flow_comp_m_x);
24507 __tmp.put_f32_le(self.flow_comp_m_y);
24508 __tmp.put_f32_le(self.ground_distance);
24509 __tmp.put_i16_le(self.flow_x);
24510 __tmp.put_i16_le(self.flow_y);
24511 __tmp.put_u8(self.sensor_id);
24512 __tmp.put_u8(self.quality);
24513 if matches!(version, MavlinkVersion::V2) {
24514 __tmp.put_f32_le(self.flow_rate_x);
24515 __tmp.put_f32_le(self.flow_rate_y);
24516 let len = __tmp.len();
24517 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24518 } else {
24519 __tmp.len()
24520 }
24521 }
24522}
24523#[doc = "Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse sensor)."]
24524#[doc = ""]
24525#[doc = "ID: 106"]
24526#[derive(Debug, Clone, PartialEq)]
24527#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24528#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24529#[cfg_attr(feature = "ts", derive(TS))]
24530#[cfg_attr(feature = "ts", ts(export))]
24531pub struct OPTICAL_FLOW_RAD_DATA {
24532 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
24533 pub time_usec: u64,
24534 #[doc = "Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the."]
24535 pub integration_time_us: u32,
24536 #[doc = "Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)"]
24537 pub integrated_x: f32,
24538 #[doc = "Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)"]
24539 pub integrated_y: f32,
24540 #[doc = "RH rotation around X axis"]
24541 pub integrated_xgyro: f32,
24542 #[doc = "RH rotation around Y axis"]
24543 pub integrated_ygyro: f32,
24544 #[doc = "RH rotation around Z axis"]
24545 pub integrated_zgyro: f32,
24546 #[doc = "Time since the distance was sampled."]
24547 pub time_delta_distance_us: u32,
24548 #[doc = "Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance."]
24549 pub distance: f32,
24550 #[doc = "Temperature"]
24551 pub temperature: i16,
24552 #[doc = "Sensor ID"]
24553 pub sensor_id: u8,
24554 #[doc = "Optical flow quality / confidence. 0: no valid flow, 255: maximum quality"]
24555 pub quality: u8,
24556}
24557impl OPTICAL_FLOW_RAD_DATA {
24558 pub const ENCODED_LEN: usize = 44usize;
24559 pub const DEFAULT: Self = Self {
24560 time_usec: 0_u64,
24561 integration_time_us: 0_u32,
24562 integrated_x: 0.0_f32,
24563 integrated_y: 0.0_f32,
24564 integrated_xgyro: 0.0_f32,
24565 integrated_ygyro: 0.0_f32,
24566 integrated_zgyro: 0.0_f32,
24567 time_delta_distance_us: 0_u32,
24568 distance: 0.0_f32,
24569 temperature: 0_i16,
24570 sensor_id: 0_u8,
24571 quality: 0_u8,
24572 };
24573 #[cfg(feature = "arbitrary")]
24574 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24575 use arbitrary::{Arbitrary, Unstructured};
24576 let mut buf = [0u8; 1024];
24577 rng.fill_bytes(&mut buf);
24578 let mut unstructured = Unstructured::new(&buf);
24579 Self::arbitrary(&mut unstructured).unwrap_or_default()
24580 }
24581}
24582impl Default for OPTICAL_FLOW_RAD_DATA {
24583 fn default() -> Self {
24584 Self::DEFAULT.clone()
24585 }
24586}
24587impl MessageData for OPTICAL_FLOW_RAD_DATA {
24588 type Message = MavMessage;
24589 const ID: u32 = 106u32;
24590 const NAME: &'static str = "OPTICAL_FLOW_RAD";
24591 const EXTRA_CRC: u8 = 138u8;
24592 const ENCODED_LEN: usize = 44usize;
24593 fn deser(
24594 _version: MavlinkVersion,
24595 __input: &[u8],
24596 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24597 let avail_len = __input.len();
24598 let mut payload_buf = [0; Self::ENCODED_LEN];
24599 let mut buf = if avail_len < Self::ENCODED_LEN {
24600 payload_buf[0..avail_len].copy_from_slice(__input);
24601 Bytes::new(&payload_buf)
24602 } else {
24603 Bytes::new(__input)
24604 };
24605 let mut __struct = Self::default();
24606 __struct.time_usec = buf.get_u64_le()?;
24607 __struct.integration_time_us = buf.get_u32_le()?;
24608 __struct.integrated_x = buf.get_f32_le()?;
24609 __struct.integrated_y = buf.get_f32_le()?;
24610 __struct.integrated_xgyro = buf.get_f32_le()?;
24611 __struct.integrated_ygyro = buf.get_f32_le()?;
24612 __struct.integrated_zgyro = buf.get_f32_le()?;
24613 __struct.time_delta_distance_us = buf.get_u32_le()?;
24614 __struct.distance = buf.get_f32_le()?;
24615 __struct.temperature = buf.get_i16_le()?;
24616 __struct.sensor_id = buf.get_u8()?;
24617 __struct.quality = buf.get_u8()?;
24618 Ok(__struct)
24619 }
24620 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24621 let mut __tmp = BytesMut::new(bytes);
24622 #[allow(clippy::absurd_extreme_comparisons)]
24623 #[allow(unused_comparisons)]
24624 if __tmp.remaining() < Self::ENCODED_LEN {
24625 panic!(
24626 "buffer is too small (need {} bytes, but got {})",
24627 Self::ENCODED_LEN,
24628 __tmp.remaining(),
24629 )
24630 }
24631 __tmp.put_u64_le(self.time_usec);
24632 __tmp.put_u32_le(self.integration_time_us);
24633 __tmp.put_f32_le(self.integrated_x);
24634 __tmp.put_f32_le(self.integrated_y);
24635 __tmp.put_f32_le(self.integrated_xgyro);
24636 __tmp.put_f32_le(self.integrated_ygyro);
24637 __tmp.put_f32_le(self.integrated_zgyro);
24638 __tmp.put_u32_le(self.time_delta_distance_us);
24639 __tmp.put_f32_le(self.distance);
24640 __tmp.put_i16_le(self.temperature);
24641 __tmp.put_u8(self.sensor_id);
24642 __tmp.put_u8(self.quality);
24643 if matches!(version, MavlinkVersion::V2) {
24644 let len = __tmp.len();
24645 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24646 } else {
24647 __tmp.len()
24648 }
24649 }
24650}
24651#[doc = "Vehicle status report that is sent out while orbit execution is in progress (see MAV_CMD_DO_ORBIT)."]
24652#[doc = ""]
24653#[doc = "ID: 360"]
24654#[derive(Debug, Clone, PartialEq)]
24655#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24656#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24657#[cfg_attr(feature = "ts", derive(TS))]
24658#[cfg_attr(feature = "ts", ts(export))]
24659pub struct ORBIT_EXECUTION_STATUS_DATA {
24660 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
24661 pub time_usec: u64,
24662 #[doc = "Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise."]
24663 pub radius: f32,
24664 #[doc = "X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7."]
24665 pub x: i32,
24666 #[doc = "Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7."]
24667 pub y: i32,
24668 #[doc = "Altitude of center point. Coordinate system depends on frame field."]
24669 pub z: f32,
24670 #[doc = "The coordinate system of the fields: x, y, z."]
24671 pub frame: MavFrame,
24672}
24673impl ORBIT_EXECUTION_STATUS_DATA {
24674 pub const ENCODED_LEN: usize = 25usize;
24675 pub const DEFAULT: Self = Self {
24676 time_usec: 0_u64,
24677 radius: 0.0_f32,
24678 x: 0_i32,
24679 y: 0_i32,
24680 z: 0.0_f32,
24681 frame: MavFrame::DEFAULT,
24682 };
24683 #[cfg(feature = "arbitrary")]
24684 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24685 use arbitrary::{Arbitrary, Unstructured};
24686 let mut buf = [0u8; 1024];
24687 rng.fill_bytes(&mut buf);
24688 let mut unstructured = Unstructured::new(&buf);
24689 Self::arbitrary(&mut unstructured).unwrap_or_default()
24690 }
24691}
24692impl Default for ORBIT_EXECUTION_STATUS_DATA {
24693 fn default() -> Self {
24694 Self::DEFAULT.clone()
24695 }
24696}
24697impl MessageData for ORBIT_EXECUTION_STATUS_DATA {
24698 type Message = MavMessage;
24699 const ID: u32 = 360u32;
24700 const NAME: &'static str = "ORBIT_EXECUTION_STATUS";
24701 const EXTRA_CRC: u8 = 11u8;
24702 const ENCODED_LEN: usize = 25usize;
24703 fn deser(
24704 _version: MavlinkVersion,
24705 __input: &[u8],
24706 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24707 let avail_len = __input.len();
24708 let mut payload_buf = [0; Self::ENCODED_LEN];
24709 let mut buf = if avail_len < Self::ENCODED_LEN {
24710 payload_buf[0..avail_len].copy_from_slice(__input);
24711 Bytes::new(&payload_buf)
24712 } else {
24713 Bytes::new(__input)
24714 };
24715 let mut __struct = Self::default();
24716 __struct.time_usec = buf.get_u64_le()?;
24717 __struct.radius = buf.get_f32_le()?;
24718 __struct.x = buf.get_i32_le()?;
24719 __struct.y = buf.get_i32_le()?;
24720 __struct.z = buf.get_f32_le()?;
24721 let tmp = buf.get_u8()?;
24722 __struct.frame =
24723 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
24724 enum_type: "MavFrame",
24725 value: tmp as u64,
24726 })?;
24727 Ok(__struct)
24728 }
24729 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24730 let mut __tmp = BytesMut::new(bytes);
24731 #[allow(clippy::absurd_extreme_comparisons)]
24732 #[allow(unused_comparisons)]
24733 if __tmp.remaining() < Self::ENCODED_LEN {
24734 panic!(
24735 "buffer is too small (need {} bytes, but got {})",
24736 Self::ENCODED_LEN,
24737 __tmp.remaining(),
24738 )
24739 }
24740 __tmp.put_u64_le(self.time_usec);
24741 __tmp.put_f32_le(self.radius);
24742 __tmp.put_i32_le(self.x);
24743 __tmp.put_i32_le(self.y);
24744 __tmp.put_f32_le(self.z);
24745 __tmp.put_u8(self.frame as u8);
24746 if matches!(version, MavlinkVersion::V2) {
24747 let len = __tmp.len();
24748 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24749 } else {
24750 __tmp.len()
24751 }
24752 }
24753}
24754#[doc = "Response from a PARAM_EXT_SET message."]
24755#[doc = ""]
24756#[doc = "ID: 324"]
24757#[derive(Debug, Clone, PartialEq)]
24758#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24759#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24760#[cfg_attr(feature = "ts", derive(TS))]
24761#[cfg_attr(feature = "ts", ts(export))]
24762pub struct PARAM_EXT_ACK_DATA {
24763 #[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
24764 #[cfg_attr(feature = "ts", ts(type = "string"))]
24765 pub param_id: CharArray<16>,
24766 #[doc = "Parameter value (new value if PARAM_ACK_ACCEPTED, current value otherwise)"]
24767 #[cfg_attr(feature = "ts", ts(type = "string"))]
24768 pub param_value: CharArray<128>,
24769 #[doc = "Parameter type."]
24770 pub param_type: MavParamExtType,
24771 #[doc = "Result code."]
24772 pub param_result: ParamAck,
24773}
24774impl PARAM_EXT_ACK_DATA {
24775 pub const ENCODED_LEN: usize = 146usize;
24776 pub const DEFAULT: Self = Self {
24777 param_id: CharArray::new([0_u8; 16usize]),
24778 param_value: CharArray::new([0_u8; 128usize]),
24779 param_type: MavParamExtType::DEFAULT,
24780 param_result: ParamAck::DEFAULT,
24781 };
24782 #[cfg(feature = "arbitrary")]
24783 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24784 use arbitrary::{Arbitrary, Unstructured};
24785 let mut buf = [0u8; 1024];
24786 rng.fill_bytes(&mut buf);
24787 let mut unstructured = Unstructured::new(&buf);
24788 Self::arbitrary(&mut unstructured).unwrap_or_default()
24789 }
24790}
24791impl Default for PARAM_EXT_ACK_DATA {
24792 fn default() -> Self {
24793 Self::DEFAULT.clone()
24794 }
24795}
24796impl MessageData for PARAM_EXT_ACK_DATA {
24797 type Message = MavMessage;
24798 const ID: u32 = 324u32;
24799 const NAME: &'static str = "PARAM_EXT_ACK";
24800 const EXTRA_CRC: u8 = 132u8;
24801 const ENCODED_LEN: usize = 146usize;
24802 fn deser(
24803 _version: MavlinkVersion,
24804 __input: &[u8],
24805 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24806 let avail_len = __input.len();
24807 let mut payload_buf = [0; Self::ENCODED_LEN];
24808 let mut buf = if avail_len < Self::ENCODED_LEN {
24809 payload_buf[0..avail_len].copy_from_slice(__input);
24810 Bytes::new(&payload_buf)
24811 } else {
24812 Bytes::new(__input)
24813 };
24814 let mut __struct = Self::default();
24815 let mut tmp = [0_u8; 16usize];
24816 for v in &mut tmp {
24817 *v = buf.get_u8()?;
24818 }
24819 __struct.param_id = CharArray::new(tmp);
24820 let mut tmp = [0_u8; 128usize];
24821 for v in &mut tmp {
24822 *v = buf.get_u8()?;
24823 }
24824 __struct.param_value = CharArray::new(tmp);
24825 let tmp = buf.get_u8()?;
24826 __struct.param_type =
24827 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
24828 enum_type: "MavParamExtType",
24829 value: tmp as u64,
24830 })?;
24831 let tmp = buf.get_u8()?;
24832 __struct.param_result =
24833 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
24834 enum_type: "ParamAck",
24835 value: tmp as u64,
24836 })?;
24837 Ok(__struct)
24838 }
24839 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24840 let mut __tmp = BytesMut::new(bytes);
24841 #[allow(clippy::absurd_extreme_comparisons)]
24842 #[allow(unused_comparisons)]
24843 if __tmp.remaining() < Self::ENCODED_LEN {
24844 panic!(
24845 "buffer is too small (need {} bytes, but got {})",
24846 Self::ENCODED_LEN,
24847 __tmp.remaining(),
24848 )
24849 }
24850 for val in &self.param_id {
24851 __tmp.put_u8(*val);
24852 }
24853 for val in &self.param_value {
24854 __tmp.put_u8(*val);
24855 }
24856 __tmp.put_u8(self.param_type as u8);
24857 __tmp.put_u8(self.param_result as u8);
24858 if matches!(version, MavlinkVersion::V2) {
24859 let len = __tmp.len();
24860 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24861 } else {
24862 __tmp.len()
24863 }
24864 }
24865}
24866#[doc = "Request all parameters of this component. All parameters should be emitted in response as PARAM_EXT_VALUE."]
24867#[doc = ""]
24868#[doc = "ID: 321"]
24869#[derive(Debug, Clone, PartialEq)]
24870#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24871#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24872#[cfg_attr(feature = "ts", derive(TS))]
24873#[cfg_attr(feature = "ts", ts(export))]
24874pub struct PARAM_EXT_REQUEST_LIST_DATA {
24875 #[doc = "System ID"]
24876 pub target_system: u8,
24877 #[doc = "Component ID"]
24878 pub target_component: u8,
24879}
24880impl PARAM_EXT_REQUEST_LIST_DATA {
24881 pub const ENCODED_LEN: usize = 2usize;
24882 pub const DEFAULT: Self = Self {
24883 target_system: 0_u8,
24884 target_component: 0_u8,
24885 };
24886 #[cfg(feature = "arbitrary")]
24887 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24888 use arbitrary::{Arbitrary, Unstructured};
24889 let mut buf = [0u8; 1024];
24890 rng.fill_bytes(&mut buf);
24891 let mut unstructured = Unstructured::new(&buf);
24892 Self::arbitrary(&mut unstructured).unwrap_or_default()
24893 }
24894}
24895impl Default for PARAM_EXT_REQUEST_LIST_DATA {
24896 fn default() -> Self {
24897 Self::DEFAULT.clone()
24898 }
24899}
24900impl MessageData for PARAM_EXT_REQUEST_LIST_DATA {
24901 type Message = MavMessage;
24902 const ID: u32 = 321u32;
24903 const NAME: &'static str = "PARAM_EXT_REQUEST_LIST";
24904 const EXTRA_CRC: u8 = 88u8;
24905 const ENCODED_LEN: usize = 2usize;
24906 fn deser(
24907 _version: MavlinkVersion,
24908 __input: &[u8],
24909 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24910 let avail_len = __input.len();
24911 let mut payload_buf = [0; Self::ENCODED_LEN];
24912 let mut buf = if avail_len < Self::ENCODED_LEN {
24913 payload_buf[0..avail_len].copy_from_slice(__input);
24914 Bytes::new(&payload_buf)
24915 } else {
24916 Bytes::new(__input)
24917 };
24918 let mut __struct = Self::default();
24919 __struct.target_system = buf.get_u8()?;
24920 __struct.target_component = buf.get_u8()?;
24921 Ok(__struct)
24922 }
24923 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24924 let mut __tmp = BytesMut::new(bytes);
24925 #[allow(clippy::absurd_extreme_comparisons)]
24926 #[allow(unused_comparisons)]
24927 if __tmp.remaining() < Self::ENCODED_LEN {
24928 panic!(
24929 "buffer is too small (need {} bytes, but got {})",
24930 Self::ENCODED_LEN,
24931 __tmp.remaining(),
24932 )
24933 }
24934 __tmp.put_u8(self.target_system);
24935 __tmp.put_u8(self.target_component);
24936 if matches!(version, MavlinkVersion::V2) {
24937 let len = __tmp.len();
24938 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24939 } else {
24940 __tmp.len()
24941 }
24942 }
24943}
24944#[doc = "Request to read the value of a parameter with either the param_id string id or param_index. PARAM_EXT_VALUE should be emitted in response."]
24945#[doc = ""]
24946#[doc = "ID: 320"]
24947#[derive(Debug, Clone, PartialEq)]
24948#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24949#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24950#[cfg_attr(feature = "ts", derive(TS))]
24951#[cfg_attr(feature = "ts", ts(export))]
24952pub struct PARAM_EXT_REQUEST_READ_DATA {
24953 #[doc = "Parameter index. Set to -1 to use the Parameter ID field as identifier (else param_id will be ignored)"]
24954 pub param_index: i16,
24955 #[doc = "System ID"]
24956 pub target_system: u8,
24957 #[doc = "Component ID"]
24958 pub target_component: u8,
24959 #[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
24960 #[cfg_attr(feature = "ts", ts(type = "string"))]
24961 pub param_id: CharArray<16>,
24962}
24963impl PARAM_EXT_REQUEST_READ_DATA {
24964 pub const ENCODED_LEN: usize = 20usize;
24965 pub const DEFAULT: Self = Self {
24966 param_index: 0_i16,
24967 target_system: 0_u8,
24968 target_component: 0_u8,
24969 param_id: CharArray::new([0_u8; 16usize]),
24970 };
24971 #[cfg(feature = "arbitrary")]
24972 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24973 use arbitrary::{Arbitrary, Unstructured};
24974 let mut buf = [0u8; 1024];
24975 rng.fill_bytes(&mut buf);
24976 let mut unstructured = Unstructured::new(&buf);
24977 Self::arbitrary(&mut unstructured).unwrap_or_default()
24978 }
24979}
24980impl Default for PARAM_EXT_REQUEST_READ_DATA {
24981 fn default() -> Self {
24982 Self::DEFAULT.clone()
24983 }
24984}
24985impl MessageData for PARAM_EXT_REQUEST_READ_DATA {
24986 type Message = MavMessage;
24987 const ID: u32 = 320u32;
24988 const NAME: &'static str = "PARAM_EXT_REQUEST_READ";
24989 const EXTRA_CRC: u8 = 243u8;
24990 const ENCODED_LEN: usize = 20usize;
24991 fn deser(
24992 _version: MavlinkVersion,
24993 __input: &[u8],
24994 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24995 let avail_len = __input.len();
24996 let mut payload_buf = [0; Self::ENCODED_LEN];
24997 let mut buf = if avail_len < Self::ENCODED_LEN {
24998 payload_buf[0..avail_len].copy_from_slice(__input);
24999 Bytes::new(&payload_buf)
25000 } else {
25001 Bytes::new(__input)
25002 };
25003 let mut __struct = Self::default();
25004 __struct.param_index = buf.get_i16_le()?;
25005 __struct.target_system = buf.get_u8()?;
25006 __struct.target_component = buf.get_u8()?;
25007 let mut tmp = [0_u8; 16usize];
25008 for v in &mut tmp {
25009 *v = buf.get_u8()?;
25010 }
25011 __struct.param_id = CharArray::new(tmp);
25012 Ok(__struct)
25013 }
25014 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25015 let mut __tmp = BytesMut::new(bytes);
25016 #[allow(clippy::absurd_extreme_comparisons)]
25017 #[allow(unused_comparisons)]
25018 if __tmp.remaining() < Self::ENCODED_LEN {
25019 panic!(
25020 "buffer is too small (need {} bytes, but got {})",
25021 Self::ENCODED_LEN,
25022 __tmp.remaining(),
25023 )
25024 }
25025 __tmp.put_i16_le(self.param_index);
25026 __tmp.put_u8(self.target_system);
25027 __tmp.put_u8(self.target_component);
25028 for val in &self.param_id {
25029 __tmp.put_u8(*val);
25030 }
25031 if matches!(version, MavlinkVersion::V2) {
25032 let len = __tmp.len();
25033 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25034 } else {
25035 __tmp.len()
25036 }
25037 }
25038}
25039#[doc = "Set a parameter value. In order to deal with message loss (and retransmission of PARAM_EXT_SET), when setting a parameter value and the new value is the same as the current value, you will immediately get a PARAM_ACK_ACCEPTED response. If the current state is PARAM_ACK_IN_PROGRESS, you will accordingly receive a PARAM_ACK_IN_PROGRESS in response."]
25040#[doc = ""]
25041#[doc = "ID: 323"]
25042#[derive(Debug, Clone, PartialEq)]
25043#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25044#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25045#[cfg_attr(feature = "ts", derive(TS))]
25046#[cfg_attr(feature = "ts", ts(export))]
25047pub struct PARAM_EXT_SET_DATA {
25048 #[doc = "System ID"]
25049 pub target_system: u8,
25050 #[doc = "Component ID"]
25051 pub target_component: u8,
25052 #[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
25053 #[cfg_attr(feature = "ts", ts(type = "string"))]
25054 pub param_id: CharArray<16>,
25055 #[doc = "Parameter value"]
25056 #[cfg_attr(feature = "ts", ts(type = "string"))]
25057 pub param_value: CharArray<128>,
25058 #[doc = "Parameter type."]
25059 pub param_type: MavParamExtType,
25060}
25061impl PARAM_EXT_SET_DATA {
25062 pub const ENCODED_LEN: usize = 147usize;
25063 pub const DEFAULT: Self = Self {
25064 target_system: 0_u8,
25065 target_component: 0_u8,
25066 param_id: CharArray::new([0_u8; 16usize]),
25067 param_value: CharArray::new([0_u8; 128usize]),
25068 param_type: MavParamExtType::DEFAULT,
25069 };
25070 #[cfg(feature = "arbitrary")]
25071 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25072 use arbitrary::{Arbitrary, Unstructured};
25073 let mut buf = [0u8; 1024];
25074 rng.fill_bytes(&mut buf);
25075 let mut unstructured = Unstructured::new(&buf);
25076 Self::arbitrary(&mut unstructured).unwrap_or_default()
25077 }
25078}
25079impl Default for PARAM_EXT_SET_DATA {
25080 fn default() -> Self {
25081 Self::DEFAULT.clone()
25082 }
25083}
25084impl MessageData for PARAM_EXT_SET_DATA {
25085 type Message = MavMessage;
25086 const ID: u32 = 323u32;
25087 const NAME: &'static str = "PARAM_EXT_SET";
25088 const EXTRA_CRC: u8 = 78u8;
25089 const ENCODED_LEN: usize = 147usize;
25090 fn deser(
25091 _version: MavlinkVersion,
25092 __input: &[u8],
25093 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25094 let avail_len = __input.len();
25095 let mut payload_buf = [0; Self::ENCODED_LEN];
25096 let mut buf = if avail_len < Self::ENCODED_LEN {
25097 payload_buf[0..avail_len].copy_from_slice(__input);
25098 Bytes::new(&payload_buf)
25099 } else {
25100 Bytes::new(__input)
25101 };
25102 let mut __struct = Self::default();
25103 __struct.target_system = buf.get_u8()?;
25104 __struct.target_component = buf.get_u8()?;
25105 let mut tmp = [0_u8; 16usize];
25106 for v in &mut tmp {
25107 *v = buf.get_u8()?;
25108 }
25109 __struct.param_id = CharArray::new(tmp);
25110 let mut tmp = [0_u8; 128usize];
25111 for v in &mut tmp {
25112 *v = buf.get_u8()?;
25113 }
25114 __struct.param_value = CharArray::new(tmp);
25115 let tmp = buf.get_u8()?;
25116 __struct.param_type =
25117 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
25118 enum_type: "MavParamExtType",
25119 value: tmp as u64,
25120 })?;
25121 Ok(__struct)
25122 }
25123 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25124 let mut __tmp = BytesMut::new(bytes);
25125 #[allow(clippy::absurd_extreme_comparisons)]
25126 #[allow(unused_comparisons)]
25127 if __tmp.remaining() < Self::ENCODED_LEN {
25128 panic!(
25129 "buffer is too small (need {} bytes, but got {})",
25130 Self::ENCODED_LEN,
25131 __tmp.remaining(),
25132 )
25133 }
25134 __tmp.put_u8(self.target_system);
25135 __tmp.put_u8(self.target_component);
25136 for val in &self.param_id {
25137 __tmp.put_u8(*val);
25138 }
25139 for val in &self.param_value {
25140 __tmp.put_u8(*val);
25141 }
25142 __tmp.put_u8(self.param_type as u8);
25143 if matches!(version, MavlinkVersion::V2) {
25144 let len = __tmp.len();
25145 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25146 } else {
25147 __tmp.len()
25148 }
25149 }
25150}
25151#[doc = "Emit the value of a parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows them to re-request missing parameters after a loss or timeout."]
25152#[doc = ""]
25153#[doc = "ID: 322"]
25154#[derive(Debug, Clone, PartialEq)]
25155#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25156#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25157#[cfg_attr(feature = "ts", derive(TS))]
25158#[cfg_attr(feature = "ts", ts(export))]
25159pub struct PARAM_EXT_VALUE_DATA {
25160 #[doc = "Total number of parameters"]
25161 pub param_count: u16,
25162 #[doc = "Index of this parameter"]
25163 pub param_index: u16,
25164 #[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
25165 #[cfg_attr(feature = "ts", ts(type = "string"))]
25166 pub param_id: CharArray<16>,
25167 #[doc = "Parameter value"]
25168 #[cfg_attr(feature = "ts", ts(type = "string"))]
25169 pub param_value: CharArray<128>,
25170 #[doc = "Parameter type."]
25171 pub param_type: MavParamExtType,
25172}
25173impl PARAM_EXT_VALUE_DATA {
25174 pub const ENCODED_LEN: usize = 149usize;
25175 pub const DEFAULT: Self = Self {
25176 param_count: 0_u16,
25177 param_index: 0_u16,
25178 param_id: CharArray::new([0_u8; 16usize]),
25179 param_value: CharArray::new([0_u8; 128usize]),
25180 param_type: MavParamExtType::DEFAULT,
25181 };
25182 #[cfg(feature = "arbitrary")]
25183 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25184 use arbitrary::{Arbitrary, Unstructured};
25185 let mut buf = [0u8; 1024];
25186 rng.fill_bytes(&mut buf);
25187 let mut unstructured = Unstructured::new(&buf);
25188 Self::arbitrary(&mut unstructured).unwrap_or_default()
25189 }
25190}
25191impl Default for PARAM_EXT_VALUE_DATA {
25192 fn default() -> Self {
25193 Self::DEFAULT.clone()
25194 }
25195}
25196impl MessageData for PARAM_EXT_VALUE_DATA {
25197 type Message = MavMessage;
25198 const ID: u32 = 322u32;
25199 const NAME: &'static str = "PARAM_EXT_VALUE";
25200 const EXTRA_CRC: u8 = 243u8;
25201 const ENCODED_LEN: usize = 149usize;
25202 fn deser(
25203 _version: MavlinkVersion,
25204 __input: &[u8],
25205 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25206 let avail_len = __input.len();
25207 let mut payload_buf = [0; Self::ENCODED_LEN];
25208 let mut buf = if avail_len < Self::ENCODED_LEN {
25209 payload_buf[0..avail_len].copy_from_slice(__input);
25210 Bytes::new(&payload_buf)
25211 } else {
25212 Bytes::new(__input)
25213 };
25214 let mut __struct = Self::default();
25215 __struct.param_count = buf.get_u16_le()?;
25216 __struct.param_index = buf.get_u16_le()?;
25217 let mut tmp = [0_u8; 16usize];
25218 for v in &mut tmp {
25219 *v = buf.get_u8()?;
25220 }
25221 __struct.param_id = CharArray::new(tmp);
25222 let mut tmp = [0_u8; 128usize];
25223 for v in &mut tmp {
25224 *v = buf.get_u8()?;
25225 }
25226 __struct.param_value = CharArray::new(tmp);
25227 let tmp = buf.get_u8()?;
25228 __struct.param_type =
25229 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
25230 enum_type: "MavParamExtType",
25231 value: tmp as u64,
25232 })?;
25233 Ok(__struct)
25234 }
25235 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25236 let mut __tmp = BytesMut::new(bytes);
25237 #[allow(clippy::absurd_extreme_comparisons)]
25238 #[allow(unused_comparisons)]
25239 if __tmp.remaining() < Self::ENCODED_LEN {
25240 panic!(
25241 "buffer is too small (need {} bytes, but got {})",
25242 Self::ENCODED_LEN,
25243 __tmp.remaining(),
25244 )
25245 }
25246 __tmp.put_u16_le(self.param_count);
25247 __tmp.put_u16_le(self.param_index);
25248 for val in &self.param_id {
25249 __tmp.put_u8(*val);
25250 }
25251 for val in &self.param_value {
25252 __tmp.put_u8(*val);
25253 }
25254 __tmp.put_u8(self.param_type as u8);
25255 if matches!(version, MavlinkVersion::V2) {
25256 let len = __tmp.len();
25257 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25258 } else {
25259 __tmp.len()
25260 }
25261 }
25262}
25263#[doc = "Bind a RC channel to a parameter. The parameter should change according to the RC channel value."]
25264#[doc = ""]
25265#[doc = "ID: 50"]
25266#[derive(Debug, Clone, PartialEq)]
25267#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25268#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25269#[cfg_attr(feature = "ts", derive(TS))]
25270#[cfg_attr(feature = "ts", ts(export))]
25271pub struct PARAM_MAP_RC_DATA {
25272 #[doc = "Initial parameter value"]
25273 pub param_value0: f32,
25274 #[doc = "Scale, maps the RC range [-1, 1] to a parameter value"]
25275 pub scale: f32,
25276 #[doc = "Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)"]
25277 pub param_value_min: f32,
25278 #[doc = "Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)"]
25279 pub param_value_max: f32,
25280 #[doc = "Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index."]
25281 pub param_index: i16,
25282 #[doc = "System ID"]
25283 pub target_system: u8,
25284 #[doc = "Component ID"]
25285 pub target_component: u8,
25286 #[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
25287 #[cfg_attr(feature = "ts", ts(type = "string"))]
25288 pub param_id: CharArray<16>,
25289 #[doc = "Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC."]
25290 pub parameter_rc_channel_index: u8,
25291}
25292impl PARAM_MAP_RC_DATA {
25293 pub const ENCODED_LEN: usize = 37usize;
25294 pub const DEFAULT: Self = Self {
25295 param_value0: 0.0_f32,
25296 scale: 0.0_f32,
25297 param_value_min: 0.0_f32,
25298 param_value_max: 0.0_f32,
25299 param_index: 0_i16,
25300 target_system: 0_u8,
25301 target_component: 0_u8,
25302 param_id: CharArray::new([0_u8; 16usize]),
25303 parameter_rc_channel_index: 0_u8,
25304 };
25305 #[cfg(feature = "arbitrary")]
25306 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25307 use arbitrary::{Arbitrary, Unstructured};
25308 let mut buf = [0u8; 1024];
25309 rng.fill_bytes(&mut buf);
25310 let mut unstructured = Unstructured::new(&buf);
25311 Self::arbitrary(&mut unstructured).unwrap_or_default()
25312 }
25313}
25314impl Default for PARAM_MAP_RC_DATA {
25315 fn default() -> Self {
25316 Self::DEFAULT.clone()
25317 }
25318}
25319impl MessageData for PARAM_MAP_RC_DATA {
25320 type Message = MavMessage;
25321 const ID: u32 = 50u32;
25322 const NAME: &'static str = "PARAM_MAP_RC";
25323 const EXTRA_CRC: u8 = 78u8;
25324 const ENCODED_LEN: usize = 37usize;
25325 fn deser(
25326 _version: MavlinkVersion,
25327 __input: &[u8],
25328 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25329 let avail_len = __input.len();
25330 let mut payload_buf = [0; Self::ENCODED_LEN];
25331 let mut buf = if avail_len < Self::ENCODED_LEN {
25332 payload_buf[0..avail_len].copy_from_slice(__input);
25333 Bytes::new(&payload_buf)
25334 } else {
25335 Bytes::new(__input)
25336 };
25337 let mut __struct = Self::default();
25338 __struct.param_value0 = buf.get_f32_le()?;
25339 __struct.scale = buf.get_f32_le()?;
25340 __struct.param_value_min = buf.get_f32_le()?;
25341 __struct.param_value_max = buf.get_f32_le()?;
25342 __struct.param_index = buf.get_i16_le()?;
25343 __struct.target_system = buf.get_u8()?;
25344 __struct.target_component = buf.get_u8()?;
25345 let mut tmp = [0_u8; 16usize];
25346 for v in &mut tmp {
25347 *v = buf.get_u8()?;
25348 }
25349 __struct.param_id = CharArray::new(tmp);
25350 __struct.parameter_rc_channel_index = buf.get_u8()?;
25351 Ok(__struct)
25352 }
25353 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25354 let mut __tmp = BytesMut::new(bytes);
25355 #[allow(clippy::absurd_extreme_comparisons)]
25356 #[allow(unused_comparisons)]
25357 if __tmp.remaining() < Self::ENCODED_LEN {
25358 panic!(
25359 "buffer is too small (need {} bytes, but got {})",
25360 Self::ENCODED_LEN,
25361 __tmp.remaining(),
25362 )
25363 }
25364 __tmp.put_f32_le(self.param_value0);
25365 __tmp.put_f32_le(self.scale);
25366 __tmp.put_f32_le(self.param_value_min);
25367 __tmp.put_f32_le(self.param_value_max);
25368 __tmp.put_i16_le(self.param_index);
25369 __tmp.put_u8(self.target_system);
25370 __tmp.put_u8(self.target_component);
25371 for val in &self.param_id {
25372 __tmp.put_u8(*val);
25373 }
25374 __tmp.put_u8(self.parameter_rc_channel_index);
25375 if matches!(version, MavlinkVersion::V2) {
25376 let len = __tmp.len();
25377 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25378 } else {
25379 __tmp.len()
25380 }
25381 }
25382}
25383#[doc = "Request all parameters of this component. After this request, all parameters are emitted. The parameter microservice is documented at <https://mavlink.io/en/services/parameter.html>."]
25384#[doc = ""]
25385#[doc = "ID: 21"]
25386#[derive(Debug, Clone, PartialEq)]
25387#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25388#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25389#[cfg_attr(feature = "ts", derive(TS))]
25390#[cfg_attr(feature = "ts", ts(export))]
25391pub struct PARAM_REQUEST_LIST_DATA {
25392 #[doc = "System ID"]
25393 pub target_system: u8,
25394 #[doc = "Component ID"]
25395 pub target_component: u8,
25396}
25397impl PARAM_REQUEST_LIST_DATA {
25398 pub const ENCODED_LEN: usize = 2usize;
25399 pub const DEFAULT: Self = Self {
25400 target_system: 0_u8,
25401 target_component: 0_u8,
25402 };
25403 #[cfg(feature = "arbitrary")]
25404 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25405 use arbitrary::{Arbitrary, Unstructured};
25406 let mut buf = [0u8; 1024];
25407 rng.fill_bytes(&mut buf);
25408 let mut unstructured = Unstructured::new(&buf);
25409 Self::arbitrary(&mut unstructured).unwrap_or_default()
25410 }
25411}
25412impl Default for PARAM_REQUEST_LIST_DATA {
25413 fn default() -> Self {
25414 Self::DEFAULT.clone()
25415 }
25416}
25417impl MessageData for PARAM_REQUEST_LIST_DATA {
25418 type Message = MavMessage;
25419 const ID: u32 = 21u32;
25420 const NAME: &'static str = "PARAM_REQUEST_LIST";
25421 const EXTRA_CRC: u8 = 159u8;
25422 const ENCODED_LEN: usize = 2usize;
25423 fn deser(
25424 _version: MavlinkVersion,
25425 __input: &[u8],
25426 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25427 let avail_len = __input.len();
25428 let mut payload_buf = [0; Self::ENCODED_LEN];
25429 let mut buf = if avail_len < Self::ENCODED_LEN {
25430 payload_buf[0..avail_len].copy_from_slice(__input);
25431 Bytes::new(&payload_buf)
25432 } else {
25433 Bytes::new(__input)
25434 };
25435 let mut __struct = Self::default();
25436 __struct.target_system = buf.get_u8()?;
25437 __struct.target_component = buf.get_u8()?;
25438 Ok(__struct)
25439 }
25440 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25441 let mut __tmp = BytesMut::new(bytes);
25442 #[allow(clippy::absurd_extreme_comparisons)]
25443 #[allow(unused_comparisons)]
25444 if __tmp.remaining() < Self::ENCODED_LEN {
25445 panic!(
25446 "buffer is too small (need {} bytes, but got {})",
25447 Self::ENCODED_LEN,
25448 __tmp.remaining(),
25449 )
25450 }
25451 __tmp.put_u8(self.target_system);
25452 __tmp.put_u8(self.target_component);
25453 if matches!(version, MavlinkVersion::V2) {
25454 let len = __tmp.len();
25455 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25456 } else {
25457 __tmp.len()
25458 }
25459 }
25460}
25461#[doc = "Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] ->value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also <https://mavlink.io/en/services/parameter.html> for a full documentation of QGroundControl and IMU code."]
25462#[doc = ""]
25463#[doc = "ID: 20"]
25464#[derive(Debug, Clone, PartialEq)]
25465#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25466#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25467#[cfg_attr(feature = "ts", derive(TS))]
25468#[cfg_attr(feature = "ts", ts(export))]
25469pub struct PARAM_REQUEST_READ_DATA {
25470 #[doc = "Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)"]
25471 pub param_index: i16,
25472 #[doc = "System ID"]
25473 pub target_system: u8,
25474 #[doc = "Component ID"]
25475 pub target_component: u8,
25476 #[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
25477 #[cfg_attr(feature = "ts", ts(type = "string"))]
25478 pub param_id: CharArray<16>,
25479}
25480impl PARAM_REQUEST_READ_DATA {
25481 pub const ENCODED_LEN: usize = 20usize;
25482 pub const DEFAULT: Self = Self {
25483 param_index: 0_i16,
25484 target_system: 0_u8,
25485 target_component: 0_u8,
25486 param_id: CharArray::new([0_u8; 16usize]),
25487 };
25488 #[cfg(feature = "arbitrary")]
25489 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25490 use arbitrary::{Arbitrary, Unstructured};
25491 let mut buf = [0u8; 1024];
25492 rng.fill_bytes(&mut buf);
25493 let mut unstructured = Unstructured::new(&buf);
25494 Self::arbitrary(&mut unstructured).unwrap_or_default()
25495 }
25496}
25497impl Default for PARAM_REQUEST_READ_DATA {
25498 fn default() -> Self {
25499 Self::DEFAULT.clone()
25500 }
25501}
25502impl MessageData for PARAM_REQUEST_READ_DATA {
25503 type Message = MavMessage;
25504 const ID: u32 = 20u32;
25505 const NAME: &'static str = "PARAM_REQUEST_READ";
25506 const EXTRA_CRC: u8 = 214u8;
25507 const ENCODED_LEN: usize = 20usize;
25508 fn deser(
25509 _version: MavlinkVersion,
25510 __input: &[u8],
25511 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25512 let avail_len = __input.len();
25513 let mut payload_buf = [0; Self::ENCODED_LEN];
25514 let mut buf = if avail_len < Self::ENCODED_LEN {
25515 payload_buf[0..avail_len].copy_from_slice(__input);
25516 Bytes::new(&payload_buf)
25517 } else {
25518 Bytes::new(__input)
25519 };
25520 let mut __struct = Self::default();
25521 __struct.param_index = buf.get_i16_le()?;
25522 __struct.target_system = buf.get_u8()?;
25523 __struct.target_component = buf.get_u8()?;
25524 let mut tmp = [0_u8; 16usize];
25525 for v in &mut tmp {
25526 *v = buf.get_u8()?;
25527 }
25528 __struct.param_id = CharArray::new(tmp);
25529 Ok(__struct)
25530 }
25531 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25532 let mut __tmp = BytesMut::new(bytes);
25533 #[allow(clippy::absurd_extreme_comparisons)]
25534 #[allow(unused_comparisons)]
25535 if __tmp.remaining() < Self::ENCODED_LEN {
25536 panic!(
25537 "buffer is too small (need {} bytes, but got {})",
25538 Self::ENCODED_LEN,
25539 __tmp.remaining(),
25540 )
25541 }
25542 __tmp.put_i16_le(self.param_index);
25543 __tmp.put_u8(self.target_system);
25544 __tmp.put_u8(self.target_component);
25545 for val in &self.param_id {
25546 __tmp.put_u8(*val);
25547 }
25548 if matches!(version, MavlinkVersion::V2) {
25549 let len = __tmp.len();
25550 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25551 } else {
25552 __tmp.len()
25553 }
25554 }
25555}
25556#[doc = "Set a parameter value (write new value to permanent storage). The receiving component should acknowledge the new parameter value by broadcasting a PARAM_VALUE message (broadcasting ensures that multiple GCS all have an up-to-date list of all parameters). If the sending GCS did not receive a PARAM_VALUE within its timeout time, it should re-send the PARAM_SET message. The parameter microservice is documented at <https://mavlink.io/en/services/parameter.html>."]
25557#[doc = ""]
25558#[doc = "ID: 23"]
25559#[derive(Debug, Clone, PartialEq)]
25560#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25561#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25562#[cfg_attr(feature = "ts", derive(TS))]
25563#[cfg_attr(feature = "ts", ts(export))]
25564pub struct PARAM_SET_DATA {
25565 #[doc = "Onboard parameter value"]
25566 pub param_value: f32,
25567 #[doc = "System ID"]
25568 pub target_system: u8,
25569 #[doc = "Component ID"]
25570 pub target_component: u8,
25571 #[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
25572 #[cfg_attr(feature = "ts", ts(type = "string"))]
25573 pub param_id: CharArray<16>,
25574 #[doc = "Onboard parameter type."]
25575 pub param_type: MavParamType,
25576}
25577impl PARAM_SET_DATA {
25578 pub const ENCODED_LEN: usize = 23usize;
25579 pub const DEFAULT: Self = Self {
25580 param_value: 0.0_f32,
25581 target_system: 0_u8,
25582 target_component: 0_u8,
25583 param_id: CharArray::new([0_u8; 16usize]),
25584 param_type: MavParamType::DEFAULT,
25585 };
25586 #[cfg(feature = "arbitrary")]
25587 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25588 use arbitrary::{Arbitrary, Unstructured};
25589 let mut buf = [0u8; 1024];
25590 rng.fill_bytes(&mut buf);
25591 let mut unstructured = Unstructured::new(&buf);
25592 Self::arbitrary(&mut unstructured).unwrap_or_default()
25593 }
25594}
25595impl Default for PARAM_SET_DATA {
25596 fn default() -> Self {
25597 Self::DEFAULT.clone()
25598 }
25599}
25600impl MessageData for PARAM_SET_DATA {
25601 type Message = MavMessage;
25602 const ID: u32 = 23u32;
25603 const NAME: &'static str = "PARAM_SET";
25604 const EXTRA_CRC: u8 = 168u8;
25605 const ENCODED_LEN: usize = 23usize;
25606 fn deser(
25607 _version: MavlinkVersion,
25608 __input: &[u8],
25609 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25610 let avail_len = __input.len();
25611 let mut payload_buf = [0; Self::ENCODED_LEN];
25612 let mut buf = if avail_len < Self::ENCODED_LEN {
25613 payload_buf[0..avail_len].copy_from_slice(__input);
25614 Bytes::new(&payload_buf)
25615 } else {
25616 Bytes::new(__input)
25617 };
25618 let mut __struct = Self::default();
25619 __struct.param_value = buf.get_f32_le()?;
25620 __struct.target_system = buf.get_u8()?;
25621 __struct.target_component = buf.get_u8()?;
25622 let mut tmp = [0_u8; 16usize];
25623 for v in &mut tmp {
25624 *v = buf.get_u8()?;
25625 }
25626 __struct.param_id = CharArray::new(tmp);
25627 let tmp = buf.get_u8()?;
25628 __struct.param_type =
25629 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
25630 enum_type: "MavParamType",
25631 value: tmp as u64,
25632 })?;
25633 Ok(__struct)
25634 }
25635 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25636 let mut __tmp = BytesMut::new(bytes);
25637 #[allow(clippy::absurd_extreme_comparisons)]
25638 #[allow(unused_comparisons)]
25639 if __tmp.remaining() < Self::ENCODED_LEN {
25640 panic!(
25641 "buffer is too small (need {} bytes, but got {})",
25642 Self::ENCODED_LEN,
25643 __tmp.remaining(),
25644 )
25645 }
25646 __tmp.put_f32_le(self.param_value);
25647 __tmp.put_u8(self.target_system);
25648 __tmp.put_u8(self.target_component);
25649 for val in &self.param_id {
25650 __tmp.put_u8(*val);
25651 }
25652 __tmp.put_u8(self.param_type as u8);
25653 if matches!(version, MavlinkVersion::V2) {
25654 let len = __tmp.len();
25655 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25656 } else {
25657 __tmp.len()
25658 }
25659 }
25660}
25661#[doc = "Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. The parameter microservice is documented at <https://mavlink.io/en/services/parameter.html>."]
25662#[doc = ""]
25663#[doc = "ID: 22"]
25664#[derive(Debug, Clone, PartialEq)]
25665#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25666#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25667#[cfg_attr(feature = "ts", derive(TS))]
25668#[cfg_attr(feature = "ts", ts(export))]
25669pub struct PARAM_VALUE_DATA {
25670 #[doc = "Onboard parameter value"]
25671 pub param_value: f32,
25672 #[doc = "Total number of onboard parameters"]
25673 pub param_count: u16,
25674 #[doc = "Index of this onboard parameter"]
25675 pub param_index: u16,
25676 #[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
25677 #[cfg_attr(feature = "ts", ts(type = "string"))]
25678 pub param_id: CharArray<16>,
25679 #[doc = "Onboard parameter type."]
25680 pub param_type: MavParamType,
25681}
25682impl PARAM_VALUE_DATA {
25683 pub const ENCODED_LEN: usize = 25usize;
25684 pub const DEFAULT: Self = Self {
25685 param_value: 0.0_f32,
25686 param_count: 0_u16,
25687 param_index: 0_u16,
25688 param_id: CharArray::new([0_u8; 16usize]),
25689 param_type: MavParamType::DEFAULT,
25690 };
25691 #[cfg(feature = "arbitrary")]
25692 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25693 use arbitrary::{Arbitrary, Unstructured};
25694 let mut buf = [0u8; 1024];
25695 rng.fill_bytes(&mut buf);
25696 let mut unstructured = Unstructured::new(&buf);
25697 Self::arbitrary(&mut unstructured).unwrap_or_default()
25698 }
25699}
25700impl Default for PARAM_VALUE_DATA {
25701 fn default() -> Self {
25702 Self::DEFAULT.clone()
25703 }
25704}
25705impl MessageData for PARAM_VALUE_DATA {
25706 type Message = MavMessage;
25707 const ID: u32 = 22u32;
25708 const NAME: &'static str = "PARAM_VALUE";
25709 const EXTRA_CRC: u8 = 220u8;
25710 const ENCODED_LEN: usize = 25usize;
25711 fn deser(
25712 _version: MavlinkVersion,
25713 __input: &[u8],
25714 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25715 let avail_len = __input.len();
25716 let mut payload_buf = [0; Self::ENCODED_LEN];
25717 let mut buf = if avail_len < Self::ENCODED_LEN {
25718 payload_buf[0..avail_len].copy_from_slice(__input);
25719 Bytes::new(&payload_buf)
25720 } else {
25721 Bytes::new(__input)
25722 };
25723 let mut __struct = Self::default();
25724 __struct.param_value = buf.get_f32_le()?;
25725 __struct.param_count = buf.get_u16_le()?;
25726 __struct.param_index = buf.get_u16_le()?;
25727 let mut tmp = [0_u8; 16usize];
25728 for v in &mut tmp {
25729 *v = buf.get_u8()?;
25730 }
25731 __struct.param_id = CharArray::new(tmp);
25732 let tmp = buf.get_u8()?;
25733 __struct.param_type =
25734 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
25735 enum_type: "MavParamType",
25736 value: tmp as u64,
25737 })?;
25738 Ok(__struct)
25739 }
25740 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25741 let mut __tmp = BytesMut::new(bytes);
25742 #[allow(clippy::absurd_extreme_comparisons)]
25743 #[allow(unused_comparisons)]
25744 if __tmp.remaining() < Self::ENCODED_LEN {
25745 panic!(
25746 "buffer is too small (need {} bytes, but got {})",
25747 Self::ENCODED_LEN,
25748 __tmp.remaining(),
25749 )
25750 }
25751 __tmp.put_f32_le(self.param_value);
25752 __tmp.put_u16_le(self.param_count);
25753 __tmp.put_u16_le(self.param_index);
25754 for val in &self.param_id {
25755 __tmp.put_u8(*val);
25756 }
25757 __tmp.put_u8(self.param_type as u8);
25758 if matches!(version, MavlinkVersion::V2) {
25759 let len = __tmp.len();
25760 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25761 } else {
25762 __tmp.len()
25763 }
25764 }
25765}
25766#[deprecated = "To be removed / merged with TIMESYNC. See `TIMESYNC` (Deprecated since 2011-08)"]
25767#[doc = "A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. The ping microservice is documented at <https://mavlink.io/en/services/ping.html>."]
25768#[doc = ""]
25769#[doc = "ID: 4"]
25770#[derive(Debug, Clone, PartialEq)]
25771#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25772#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25773#[cfg_attr(feature = "ts", derive(TS))]
25774#[cfg_attr(feature = "ts", ts(export))]
25775pub struct PING_DATA {
25776 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
25777 pub time_usec: u64,
25778 #[doc = "PING sequence"]
25779 pub seq: u32,
25780 #[doc = "0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system"]
25781 pub target_system: u8,
25782 #[doc = "0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component."]
25783 pub target_component: u8,
25784}
25785impl PING_DATA {
25786 pub const ENCODED_LEN: usize = 14usize;
25787 pub const DEFAULT: Self = Self {
25788 time_usec: 0_u64,
25789 seq: 0_u32,
25790 target_system: 0_u8,
25791 target_component: 0_u8,
25792 };
25793 #[cfg(feature = "arbitrary")]
25794 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25795 use arbitrary::{Arbitrary, Unstructured};
25796 let mut buf = [0u8; 1024];
25797 rng.fill_bytes(&mut buf);
25798 let mut unstructured = Unstructured::new(&buf);
25799 Self::arbitrary(&mut unstructured).unwrap_or_default()
25800 }
25801}
25802impl Default for PING_DATA {
25803 fn default() -> Self {
25804 Self::DEFAULT.clone()
25805 }
25806}
25807impl MessageData for PING_DATA {
25808 type Message = MavMessage;
25809 const ID: u32 = 4u32;
25810 const NAME: &'static str = "PING";
25811 const EXTRA_CRC: u8 = 237u8;
25812 const ENCODED_LEN: usize = 14usize;
25813 fn deser(
25814 _version: MavlinkVersion,
25815 __input: &[u8],
25816 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25817 let avail_len = __input.len();
25818 let mut payload_buf = [0; Self::ENCODED_LEN];
25819 let mut buf = if avail_len < Self::ENCODED_LEN {
25820 payload_buf[0..avail_len].copy_from_slice(__input);
25821 Bytes::new(&payload_buf)
25822 } else {
25823 Bytes::new(__input)
25824 };
25825 let mut __struct = Self::default();
25826 __struct.time_usec = buf.get_u64_le()?;
25827 __struct.seq = buf.get_u32_le()?;
25828 __struct.target_system = buf.get_u8()?;
25829 __struct.target_component = buf.get_u8()?;
25830 Ok(__struct)
25831 }
25832 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25833 let mut __tmp = BytesMut::new(bytes);
25834 #[allow(clippy::absurd_extreme_comparisons)]
25835 #[allow(unused_comparisons)]
25836 if __tmp.remaining() < Self::ENCODED_LEN {
25837 panic!(
25838 "buffer is too small (need {} bytes, but got {})",
25839 Self::ENCODED_LEN,
25840 __tmp.remaining(),
25841 )
25842 }
25843 __tmp.put_u64_le(self.time_usec);
25844 __tmp.put_u32_le(self.seq);
25845 __tmp.put_u8(self.target_system);
25846 __tmp.put_u8(self.target_component);
25847 if matches!(version, MavlinkVersion::V2) {
25848 let len = __tmp.len();
25849 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25850 } else {
25851 __tmp.len()
25852 }
25853 }
25854}
25855#[deprecated = "New version explicitly defines format. More interoperable. See `PLAY_TUNE_V2` (Deprecated since 2019-10)"]
25856#[doc = "Control vehicle tone generation (buzzer)."]
25857#[doc = ""]
25858#[doc = "ID: 258"]
25859#[derive(Debug, Clone, PartialEq)]
25860#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25861#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25862#[cfg_attr(feature = "ts", derive(TS))]
25863#[cfg_attr(feature = "ts", ts(export))]
25864pub struct PLAY_TUNE_DATA {
25865 #[doc = "System ID"]
25866 pub target_system: u8,
25867 #[doc = "Component ID"]
25868 pub target_component: u8,
25869 #[doc = "tune in board specific format"]
25870 #[cfg_attr(feature = "ts", ts(type = "string"))]
25871 pub tune: CharArray<30>,
25872 #[doc = "tune extension (appended to tune)"]
25873 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25874 #[cfg_attr(feature = "ts", ts(type = "string"))]
25875 pub tune2: CharArray<200>,
25876}
25877impl PLAY_TUNE_DATA {
25878 pub const ENCODED_LEN: usize = 232usize;
25879 pub const DEFAULT: Self = Self {
25880 target_system: 0_u8,
25881 target_component: 0_u8,
25882 tune: CharArray::new([0_u8; 30usize]),
25883 tune2: CharArray::new([0_u8; 200usize]),
25884 };
25885 #[cfg(feature = "arbitrary")]
25886 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25887 use arbitrary::{Arbitrary, Unstructured};
25888 let mut buf = [0u8; 1024];
25889 rng.fill_bytes(&mut buf);
25890 let mut unstructured = Unstructured::new(&buf);
25891 Self::arbitrary(&mut unstructured).unwrap_or_default()
25892 }
25893}
25894impl Default for PLAY_TUNE_DATA {
25895 fn default() -> Self {
25896 Self::DEFAULT.clone()
25897 }
25898}
25899impl MessageData for PLAY_TUNE_DATA {
25900 type Message = MavMessage;
25901 const ID: u32 = 258u32;
25902 const NAME: &'static str = "PLAY_TUNE";
25903 const EXTRA_CRC: u8 = 187u8;
25904 const ENCODED_LEN: usize = 232usize;
25905 fn deser(
25906 _version: MavlinkVersion,
25907 __input: &[u8],
25908 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25909 let avail_len = __input.len();
25910 let mut payload_buf = [0; Self::ENCODED_LEN];
25911 let mut buf = if avail_len < Self::ENCODED_LEN {
25912 payload_buf[0..avail_len].copy_from_slice(__input);
25913 Bytes::new(&payload_buf)
25914 } else {
25915 Bytes::new(__input)
25916 };
25917 let mut __struct = Self::default();
25918 __struct.target_system = buf.get_u8()?;
25919 __struct.target_component = buf.get_u8()?;
25920 let mut tmp = [0_u8; 30usize];
25921 for v in &mut tmp {
25922 *v = buf.get_u8()?;
25923 }
25924 __struct.tune = CharArray::new(tmp);
25925 let mut tmp = [0_u8; 200usize];
25926 for v in &mut tmp {
25927 *v = buf.get_u8()?;
25928 }
25929 __struct.tune2 = CharArray::new(tmp);
25930 Ok(__struct)
25931 }
25932 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25933 let mut __tmp = BytesMut::new(bytes);
25934 #[allow(clippy::absurd_extreme_comparisons)]
25935 #[allow(unused_comparisons)]
25936 if __tmp.remaining() < Self::ENCODED_LEN {
25937 panic!(
25938 "buffer is too small (need {} bytes, but got {})",
25939 Self::ENCODED_LEN,
25940 __tmp.remaining(),
25941 )
25942 }
25943 __tmp.put_u8(self.target_system);
25944 __tmp.put_u8(self.target_component);
25945 for val in &self.tune {
25946 __tmp.put_u8(*val);
25947 }
25948 if matches!(version, MavlinkVersion::V2) {
25949 for val in &self.tune2 {
25950 __tmp.put_u8(*val);
25951 }
25952 let len = __tmp.len();
25953 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25954 } else {
25955 __tmp.len()
25956 }
25957 }
25958}
25959#[doc = "Play vehicle tone/tune (buzzer). Supersedes message PLAY_TUNE."]
25960#[doc = ""]
25961#[doc = "ID: 400"]
25962#[derive(Debug, Clone, PartialEq)]
25963#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25964#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25965#[cfg_attr(feature = "ts", derive(TS))]
25966#[cfg_attr(feature = "ts", ts(export))]
25967pub struct PLAY_TUNE_V2_DATA {
25968 #[doc = "Tune format"]
25969 pub format: TuneFormat,
25970 #[doc = "System ID"]
25971 pub target_system: u8,
25972 #[doc = "Component ID"]
25973 pub target_component: u8,
25974 #[doc = "Tune definition as a NULL-terminated string."]
25975 #[cfg_attr(feature = "ts", ts(type = "string"))]
25976 pub tune: CharArray<248>,
25977}
25978impl PLAY_TUNE_V2_DATA {
25979 pub const ENCODED_LEN: usize = 254usize;
25980 pub const DEFAULT: Self = Self {
25981 format: TuneFormat::DEFAULT,
25982 target_system: 0_u8,
25983 target_component: 0_u8,
25984 tune: CharArray::new([0_u8; 248usize]),
25985 };
25986 #[cfg(feature = "arbitrary")]
25987 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25988 use arbitrary::{Arbitrary, Unstructured};
25989 let mut buf = [0u8; 1024];
25990 rng.fill_bytes(&mut buf);
25991 let mut unstructured = Unstructured::new(&buf);
25992 Self::arbitrary(&mut unstructured).unwrap_or_default()
25993 }
25994}
25995impl Default for PLAY_TUNE_V2_DATA {
25996 fn default() -> Self {
25997 Self::DEFAULT.clone()
25998 }
25999}
26000impl MessageData for PLAY_TUNE_V2_DATA {
26001 type Message = MavMessage;
26002 const ID: u32 = 400u32;
26003 const NAME: &'static str = "PLAY_TUNE_V2";
26004 const EXTRA_CRC: u8 = 110u8;
26005 const ENCODED_LEN: usize = 254usize;
26006 fn deser(
26007 _version: MavlinkVersion,
26008 __input: &[u8],
26009 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26010 let avail_len = __input.len();
26011 let mut payload_buf = [0; Self::ENCODED_LEN];
26012 let mut buf = if avail_len < Self::ENCODED_LEN {
26013 payload_buf[0..avail_len].copy_from_slice(__input);
26014 Bytes::new(&payload_buf)
26015 } else {
26016 Bytes::new(__input)
26017 };
26018 let mut __struct = Self::default();
26019 let tmp = buf.get_u32_le()?;
26020 __struct.format = FromPrimitive::from_u32(tmp).ok_or(
26021 ::mavlink_core::error::ParserError::InvalidEnum {
26022 enum_type: "TuneFormat",
26023 value: tmp as u64,
26024 },
26025 )?;
26026 __struct.target_system = buf.get_u8()?;
26027 __struct.target_component = buf.get_u8()?;
26028 let mut tmp = [0_u8; 248usize];
26029 for v in &mut tmp {
26030 *v = buf.get_u8()?;
26031 }
26032 __struct.tune = CharArray::new(tmp);
26033 Ok(__struct)
26034 }
26035 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26036 let mut __tmp = BytesMut::new(bytes);
26037 #[allow(clippy::absurd_extreme_comparisons)]
26038 #[allow(unused_comparisons)]
26039 if __tmp.remaining() < Self::ENCODED_LEN {
26040 panic!(
26041 "buffer is too small (need {} bytes, but got {})",
26042 Self::ENCODED_LEN,
26043 __tmp.remaining(),
26044 )
26045 }
26046 __tmp.put_u32_le(self.format as u32);
26047 __tmp.put_u8(self.target_system);
26048 __tmp.put_u8(self.target_component);
26049 for val in &self.tune {
26050 __tmp.put_u8(*val);
26051 }
26052 if matches!(version, MavlinkVersion::V2) {
26053 let len = __tmp.len();
26054 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26055 } else {
26056 __tmp.len()
26057 }
26058 }
26059}
26060#[doc = "Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being controlled this way."]
26061#[doc = ""]
26062#[doc = "ID: 87"]
26063#[derive(Debug, Clone, PartialEq)]
26064#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26065#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26066#[cfg_attr(feature = "ts", derive(TS))]
26067#[cfg_attr(feature = "ts", ts(export))]
26068pub struct POSITION_TARGET_GLOBAL_INT_DATA {
26069 #[doc = "Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency."]
26070 pub time_boot_ms: u32,
26071 #[doc = "Latitude in WGS84 frame"]
26072 pub lat_int: i32,
26073 #[doc = "Longitude in WGS84 frame"]
26074 pub lon_int: i32,
26075 #[doc = "Altitude (MSL, AGL or relative to home altitude, depending on frame)"]
26076 pub alt: f32,
26077 #[doc = "X velocity in NED frame"]
26078 pub vx: f32,
26079 #[doc = "Y velocity in NED frame"]
26080 pub vy: f32,
26081 #[doc = "Z velocity in NED frame"]
26082 pub vz: f32,
26083 #[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
26084 pub afx: f32,
26085 #[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
26086 pub afy: f32,
26087 #[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
26088 pub afz: f32,
26089 #[doc = "yaw setpoint"]
26090 pub yaw: f32,
26091 #[doc = "yaw rate setpoint"]
26092 pub yaw_rate: f32,
26093 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
26094 pub type_mask: PositionTargetTypemask,
26095 #[doc = "Valid options are: MAV_FRAME_GLOBAL = 0, MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 (MAV_FRAME_GLOBAL_INT, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT are allowed synonyms, but have been deprecated)"]
26096 pub coordinate_frame: MavFrame,
26097}
26098impl POSITION_TARGET_GLOBAL_INT_DATA {
26099 pub const ENCODED_LEN: usize = 51usize;
26100 pub const DEFAULT: Self = Self {
26101 time_boot_ms: 0_u32,
26102 lat_int: 0_i32,
26103 lon_int: 0_i32,
26104 alt: 0.0_f32,
26105 vx: 0.0_f32,
26106 vy: 0.0_f32,
26107 vz: 0.0_f32,
26108 afx: 0.0_f32,
26109 afy: 0.0_f32,
26110 afz: 0.0_f32,
26111 yaw: 0.0_f32,
26112 yaw_rate: 0.0_f32,
26113 type_mask: PositionTargetTypemask::DEFAULT,
26114 coordinate_frame: MavFrame::DEFAULT,
26115 };
26116 #[cfg(feature = "arbitrary")]
26117 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26118 use arbitrary::{Arbitrary, Unstructured};
26119 let mut buf = [0u8; 1024];
26120 rng.fill_bytes(&mut buf);
26121 let mut unstructured = Unstructured::new(&buf);
26122 Self::arbitrary(&mut unstructured).unwrap_or_default()
26123 }
26124}
26125impl Default for POSITION_TARGET_GLOBAL_INT_DATA {
26126 fn default() -> Self {
26127 Self::DEFAULT.clone()
26128 }
26129}
26130impl MessageData for POSITION_TARGET_GLOBAL_INT_DATA {
26131 type Message = MavMessage;
26132 const ID: u32 = 87u32;
26133 const NAME: &'static str = "POSITION_TARGET_GLOBAL_INT";
26134 const EXTRA_CRC: u8 = 150u8;
26135 const ENCODED_LEN: usize = 51usize;
26136 fn deser(
26137 _version: MavlinkVersion,
26138 __input: &[u8],
26139 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26140 let avail_len = __input.len();
26141 let mut payload_buf = [0; Self::ENCODED_LEN];
26142 let mut buf = if avail_len < Self::ENCODED_LEN {
26143 payload_buf[0..avail_len].copy_from_slice(__input);
26144 Bytes::new(&payload_buf)
26145 } else {
26146 Bytes::new(__input)
26147 };
26148 let mut __struct = Self::default();
26149 __struct.time_boot_ms = buf.get_u32_le()?;
26150 __struct.lat_int = buf.get_i32_le()?;
26151 __struct.lon_int = buf.get_i32_le()?;
26152 __struct.alt = buf.get_f32_le()?;
26153 __struct.vx = buf.get_f32_le()?;
26154 __struct.vy = buf.get_f32_le()?;
26155 __struct.vz = buf.get_f32_le()?;
26156 __struct.afx = buf.get_f32_le()?;
26157 __struct.afy = buf.get_f32_le()?;
26158 __struct.afz = buf.get_f32_le()?;
26159 __struct.yaw = buf.get_f32_le()?;
26160 __struct.yaw_rate = buf.get_f32_le()?;
26161 let tmp = buf.get_u16_le()?;
26162 __struct.type_mask =
26163 PositionTargetTypemask::from_bits(tmp as <PositionTargetTypemask as Flags>::Bits)
26164 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
26165 flag_type: "PositionTargetTypemask",
26166 value: tmp as u64,
26167 })?;
26168 let tmp = buf.get_u8()?;
26169 __struct.coordinate_frame =
26170 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26171 enum_type: "MavFrame",
26172 value: tmp as u64,
26173 })?;
26174 Ok(__struct)
26175 }
26176 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26177 let mut __tmp = BytesMut::new(bytes);
26178 #[allow(clippy::absurd_extreme_comparisons)]
26179 #[allow(unused_comparisons)]
26180 if __tmp.remaining() < Self::ENCODED_LEN {
26181 panic!(
26182 "buffer is too small (need {} bytes, but got {})",
26183 Self::ENCODED_LEN,
26184 __tmp.remaining(),
26185 )
26186 }
26187 __tmp.put_u32_le(self.time_boot_ms);
26188 __tmp.put_i32_le(self.lat_int);
26189 __tmp.put_i32_le(self.lon_int);
26190 __tmp.put_f32_le(self.alt);
26191 __tmp.put_f32_le(self.vx);
26192 __tmp.put_f32_le(self.vy);
26193 __tmp.put_f32_le(self.vz);
26194 __tmp.put_f32_le(self.afx);
26195 __tmp.put_f32_le(self.afy);
26196 __tmp.put_f32_le(self.afz);
26197 __tmp.put_f32_le(self.yaw);
26198 __tmp.put_f32_le(self.yaw_rate);
26199 __tmp.put_u16_le(self.type_mask.bits() as u16);
26200 __tmp.put_u8(self.coordinate_frame as u8);
26201 if matches!(version, MavlinkVersion::V2) {
26202 let len = __tmp.len();
26203 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26204 } else {
26205 __tmp.len()
26206 }
26207 }
26208}
26209#[doc = "Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_LOCAL_NED if the vehicle is being controlled this way."]
26210#[doc = ""]
26211#[doc = "ID: 85"]
26212#[derive(Debug, Clone, PartialEq)]
26213#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26214#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26215#[cfg_attr(feature = "ts", derive(TS))]
26216#[cfg_attr(feature = "ts", ts(export))]
26217pub struct POSITION_TARGET_LOCAL_NED_DATA {
26218 #[doc = "Timestamp (time since system boot)."]
26219 pub time_boot_ms: u32,
26220 #[doc = "X Position in NED frame"]
26221 pub x: f32,
26222 #[doc = "Y Position in NED frame"]
26223 pub y: f32,
26224 #[doc = "Z Position in NED frame (note, altitude is negative in NED)"]
26225 pub z: f32,
26226 #[doc = "X velocity in NED frame"]
26227 pub vx: f32,
26228 #[doc = "Y velocity in NED frame"]
26229 pub vy: f32,
26230 #[doc = "Z velocity in NED frame"]
26231 pub vz: f32,
26232 #[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
26233 pub afx: f32,
26234 #[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
26235 pub afy: f32,
26236 #[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
26237 pub afz: f32,
26238 #[doc = "yaw setpoint"]
26239 pub yaw: f32,
26240 #[doc = "yaw rate setpoint"]
26241 pub yaw_rate: f32,
26242 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
26243 pub type_mask: PositionTargetTypemask,
26244 #[doc = "Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9"]
26245 pub coordinate_frame: MavFrame,
26246}
26247impl POSITION_TARGET_LOCAL_NED_DATA {
26248 pub const ENCODED_LEN: usize = 51usize;
26249 pub const DEFAULT: Self = Self {
26250 time_boot_ms: 0_u32,
26251 x: 0.0_f32,
26252 y: 0.0_f32,
26253 z: 0.0_f32,
26254 vx: 0.0_f32,
26255 vy: 0.0_f32,
26256 vz: 0.0_f32,
26257 afx: 0.0_f32,
26258 afy: 0.0_f32,
26259 afz: 0.0_f32,
26260 yaw: 0.0_f32,
26261 yaw_rate: 0.0_f32,
26262 type_mask: PositionTargetTypemask::DEFAULT,
26263 coordinate_frame: MavFrame::DEFAULT,
26264 };
26265 #[cfg(feature = "arbitrary")]
26266 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26267 use arbitrary::{Arbitrary, Unstructured};
26268 let mut buf = [0u8; 1024];
26269 rng.fill_bytes(&mut buf);
26270 let mut unstructured = Unstructured::new(&buf);
26271 Self::arbitrary(&mut unstructured).unwrap_or_default()
26272 }
26273}
26274impl Default for POSITION_TARGET_LOCAL_NED_DATA {
26275 fn default() -> Self {
26276 Self::DEFAULT.clone()
26277 }
26278}
26279impl MessageData for POSITION_TARGET_LOCAL_NED_DATA {
26280 type Message = MavMessage;
26281 const ID: u32 = 85u32;
26282 const NAME: &'static str = "POSITION_TARGET_LOCAL_NED";
26283 const EXTRA_CRC: u8 = 140u8;
26284 const ENCODED_LEN: usize = 51usize;
26285 fn deser(
26286 _version: MavlinkVersion,
26287 __input: &[u8],
26288 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26289 let avail_len = __input.len();
26290 let mut payload_buf = [0; Self::ENCODED_LEN];
26291 let mut buf = if avail_len < Self::ENCODED_LEN {
26292 payload_buf[0..avail_len].copy_from_slice(__input);
26293 Bytes::new(&payload_buf)
26294 } else {
26295 Bytes::new(__input)
26296 };
26297 let mut __struct = Self::default();
26298 __struct.time_boot_ms = buf.get_u32_le()?;
26299 __struct.x = buf.get_f32_le()?;
26300 __struct.y = buf.get_f32_le()?;
26301 __struct.z = buf.get_f32_le()?;
26302 __struct.vx = buf.get_f32_le()?;
26303 __struct.vy = buf.get_f32_le()?;
26304 __struct.vz = buf.get_f32_le()?;
26305 __struct.afx = buf.get_f32_le()?;
26306 __struct.afy = buf.get_f32_le()?;
26307 __struct.afz = buf.get_f32_le()?;
26308 __struct.yaw = buf.get_f32_le()?;
26309 __struct.yaw_rate = buf.get_f32_le()?;
26310 let tmp = buf.get_u16_le()?;
26311 __struct.type_mask =
26312 PositionTargetTypemask::from_bits(tmp as <PositionTargetTypemask as Flags>::Bits)
26313 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
26314 flag_type: "PositionTargetTypemask",
26315 value: tmp as u64,
26316 })?;
26317 let tmp = buf.get_u8()?;
26318 __struct.coordinate_frame =
26319 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26320 enum_type: "MavFrame",
26321 value: tmp as u64,
26322 })?;
26323 Ok(__struct)
26324 }
26325 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26326 let mut __tmp = BytesMut::new(bytes);
26327 #[allow(clippy::absurd_extreme_comparisons)]
26328 #[allow(unused_comparisons)]
26329 if __tmp.remaining() < Self::ENCODED_LEN {
26330 panic!(
26331 "buffer is too small (need {} bytes, but got {})",
26332 Self::ENCODED_LEN,
26333 __tmp.remaining(),
26334 )
26335 }
26336 __tmp.put_u32_le(self.time_boot_ms);
26337 __tmp.put_f32_le(self.x);
26338 __tmp.put_f32_le(self.y);
26339 __tmp.put_f32_le(self.z);
26340 __tmp.put_f32_le(self.vx);
26341 __tmp.put_f32_le(self.vy);
26342 __tmp.put_f32_le(self.vz);
26343 __tmp.put_f32_le(self.afx);
26344 __tmp.put_f32_le(self.afy);
26345 __tmp.put_f32_le(self.afz);
26346 __tmp.put_f32_le(self.yaw);
26347 __tmp.put_f32_le(self.yaw_rate);
26348 __tmp.put_u16_le(self.type_mask.bits() as u16);
26349 __tmp.put_u8(self.coordinate_frame as u8);
26350 if matches!(version, MavlinkVersion::V2) {
26351 let len = __tmp.len();
26352 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26353 } else {
26354 __tmp.len()
26355 }
26356 }
26357}
26358#[doc = "Power supply status."]
26359#[doc = ""]
26360#[doc = "ID: 125"]
26361#[derive(Debug, Clone, PartialEq)]
26362#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26363#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26364#[cfg_attr(feature = "ts", derive(TS))]
26365#[cfg_attr(feature = "ts", ts(export))]
26366pub struct POWER_STATUS_DATA {
26367 #[doc = "5V rail voltage."]
26368 pub Vcc: u16,
26369 #[doc = "Servo rail voltage."]
26370 pub Vservo: u16,
26371 #[doc = "Bitmap of power supply status flags."]
26372 pub flags: MavPowerStatus,
26373}
26374impl POWER_STATUS_DATA {
26375 pub const ENCODED_LEN: usize = 6usize;
26376 pub const DEFAULT: Self = Self {
26377 Vcc: 0_u16,
26378 Vservo: 0_u16,
26379 flags: MavPowerStatus::DEFAULT,
26380 };
26381 #[cfg(feature = "arbitrary")]
26382 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26383 use arbitrary::{Arbitrary, Unstructured};
26384 let mut buf = [0u8; 1024];
26385 rng.fill_bytes(&mut buf);
26386 let mut unstructured = Unstructured::new(&buf);
26387 Self::arbitrary(&mut unstructured).unwrap_or_default()
26388 }
26389}
26390impl Default for POWER_STATUS_DATA {
26391 fn default() -> Self {
26392 Self::DEFAULT.clone()
26393 }
26394}
26395impl MessageData for POWER_STATUS_DATA {
26396 type Message = MavMessage;
26397 const ID: u32 = 125u32;
26398 const NAME: &'static str = "POWER_STATUS";
26399 const EXTRA_CRC: u8 = 203u8;
26400 const ENCODED_LEN: usize = 6usize;
26401 fn deser(
26402 _version: MavlinkVersion,
26403 __input: &[u8],
26404 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26405 let avail_len = __input.len();
26406 let mut payload_buf = [0; Self::ENCODED_LEN];
26407 let mut buf = if avail_len < Self::ENCODED_LEN {
26408 payload_buf[0..avail_len].copy_from_slice(__input);
26409 Bytes::new(&payload_buf)
26410 } else {
26411 Bytes::new(__input)
26412 };
26413 let mut __struct = Self::default();
26414 __struct.Vcc = buf.get_u16_le()?;
26415 __struct.Vservo = buf.get_u16_le()?;
26416 let tmp = buf.get_u16_le()?;
26417 __struct.flags = MavPowerStatus::from_bits(tmp as <MavPowerStatus as Flags>::Bits).ok_or(
26418 ::mavlink_core::error::ParserError::InvalidFlag {
26419 flag_type: "MavPowerStatus",
26420 value: tmp as u64,
26421 },
26422 )?;
26423 Ok(__struct)
26424 }
26425 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26426 let mut __tmp = BytesMut::new(bytes);
26427 #[allow(clippy::absurd_extreme_comparisons)]
26428 #[allow(unused_comparisons)]
26429 if __tmp.remaining() < Self::ENCODED_LEN {
26430 panic!(
26431 "buffer is too small (need {} bytes, but got {})",
26432 Self::ENCODED_LEN,
26433 __tmp.remaining(),
26434 )
26435 }
26436 __tmp.put_u16_le(self.Vcc);
26437 __tmp.put_u16_le(self.Vservo);
26438 __tmp.put_u16_le(self.flags.bits() as u16);
26439 if matches!(version, MavlinkVersion::V2) {
26440 let len = __tmp.len();
26441 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26442 } else {
26443 __tmp.len()
26444 }
26445 }
26446}
26447#[doc = "Version and capability of protocol version. This message can be requested with MAV_CMD_REQUEST_MESSAGE and is used as part of the handshaking to establish which MAVLink version should be used on the network. Every node should respond to a request for PROTOCOL_VERSION to enable the handshaking. Library implementers should consider adding this into the default decoding state machine to allow the protocol core to respond directly."]
26448#[doc = ""]
26449#[doc = "ID: 300"]
26450#[derive(Debug, Clone, PartialEq)]
26451#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26452#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26453#[cfg_attr(feature = "ts", derive(TS))]
26454#[cfg_attr(feature = "ts", ts(export))]
26455pub struct PROTOCOL_VERSION_DATA {
26456 #[doc = "Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc."]
26457 pub version: u16,
26458 #[doc = "Minimum MAVLink version supported"]
26459 pub min_version: u16,
26460 #[doc = "Maximum MAVLink version supported (set to the same value as version by default)"]
26461 pub max_version: u16,
26462 #[doc = "The first 8 bytes (not characters printed in hex!) of the git hash."]
26463 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26464 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
26465 pub spec_version_hash: [u8; 8],
26466 #[doc = "The first 8 bytes (not characters printed in hex!) of the git hash."]
26467 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26468 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
26469 pub library_version_hash: [u8; 8],
26470}
26471impl PROTOCOL_VERSION_DATA {
26472 pub const ENCODED_LEN: usize = 22usize;
26473 pub const DEFAULT: Self = Self {
26474 version: 0_u16,
26475 min_version: 0_u16,
26476 max_version: 0_u16,
26477 spec_version_hash: [0_u8; 8usize],
26478 library_version_hash: [0_u8; 8usize],
26479 };
26480 #[cfg(feature = "arbitrary")]
26481 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26482 use arbitrary::{Arbitrary, Unstructured};
26483 let mut buf = [0u8; 1024];
26484 rng.fill_bytes(&mut buf);
26485 let mut unstructured = Unstructured::new(&buf);
26486 Self::arbitrary(&mut unstructured).unwrap_or_default()
26487 }
26488}
26489impl Default for PROTOCOL_VERSION_DATA {
26490 fn default() -> Self {
26491 Self::DEFAULT.clone()
26492 }
26493}
26494impl MessageData for PROTOCOL_VERSION_DATA {
26495 type Message = MavMessage;
26496 const ID: u32 = 300u32;
26497 const NAME: &'static str = "PROTOCOL_VERSION";
26498 const EXTRA_CRC: u8 = 217u8;
26499 const ENCODED_LEN: usize = 22usize;
26500 fn deser(
26501 _version: MavlinkVersion,
26502 __input: &[u8],
26503 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26504 let avail_len = __input.len();
26505 let mut payload_buf = [0; Self::ENCODED_LEN];
26506 let mut buf = if avail_len < Self::ENCODED_LEN {
26507 payload_buf[0..avail_len].copy_from_slice(__input);
26508 Bytes::new(&payload_buf)
26509 } else {
26510 Bytes::new(__input)
26511 };
26512 let mut __struct = Self::default();
26513 __struct.version = buf.get_u16_le()?;
26514 __struct.min_version = buf.get_u16_le()?;
26515 __struct.max_version = buf.get_u16_le()?;
26516 for v in &mut __struct.spec_version_hash {
26517 let val = buf.get_u8()?;
26518 *v = val;
26519 }
26520 for v in &mut __struct.library_version_hash {
26521 let val = buf.get_u8()?;
26522 *v = val;
26523 }
26524 Ok(__struct)
26525 }
26526 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26527 let mut __tmp = BytesMut::new(bytes);
26528 #[allow(clippy::absurd_extreme_comparisons)]
26529 #[allow(unused_comparisons)]
26530 if __tmp.remaining() < Self::ENCODED_LEN {
26531 panic!(
26532 "buffer is too small (need {} bytes, but got {})",
26533 Self::ENCODED_LEN,
26534 __tmp.remaining(),
26535 )
26536 }
26537 __tmp.put_u16_le(self.version);
26538 __tmp.put_u16_le(self.min_version);
26539 __tmp.put_u16_le(self.max_version);
26540 for val in &self.spec_version_hash {
26541 __tmp.put_u8(*val);
26542 }
26543 for val in &self.library_version_hash {
26544 __tmp.put_u8(*val);
26545 }
26546 if matches!(version, MavlinkVersion::V2) {
26547 let len = __tmp.len();
26548 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26549 } else {
26550 __tmp.len()
26551 }
26552 }
26553}
26554#[doc = "Status generated by radio and injected into MAVLink stream."]
26555#[doc = ""]
26556#[doc = "ID: 109"]
26557#[derive(Debug, Clone, PartialEq)]
26558#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26559#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26560#[cfg_attr(feature = "ts", derive(TS))]
26561#[cfg_attr(feature = "ts", ts(export))]
26562pub struct RADIO_STATUS_DATA {
26563 #[doc = "Count of radio packet receive errors (since boot)."]
26564 pub rxerrors: u16,
26565 #[doc = "Count of error corrected radio packets (since boot)."]
26566 pub fixed: u16,
26567 #[doc = "Local (message sender) received signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
26568 pub rssi: u8,
26569 #[doc = "Remote (message receiver) signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
26570 pub remrssi: u8,
26571 #[doc = "Remaining free transmitter buffer space."]
26572 pub txbuf: u8,
26573 #[doc = "Local background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown."]
26574 pub noise: u8,
26575 #[doc = "Remote background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown."]
26576 pub remnoise: u8,
26577}
26578impl RADIO_STATUS_DATA {
26579 pub const ENCODED_LEN: usize = 9usize;
26580 pub const DEFAULT: Self = Self {
26581 rxerrors: 0_u16,
26582 fixed: 0_u16,
26583 rssi: 0_u8,
26584 remrssi: 0_u8,
26585 txbuf: 0_u8,
26586 noise: 0_u8,
26587 remnoise: 0_u8,
26588 };
26589 #[cfg(feature = "arbitrary")]
26590 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26591 use arbitrary::{Arbitrary, Unstructured};
26592 let mut buf = [0u8; 1024];
26593 rng.fill_bytes(&mut buf);
26594 let mut unstructured = Unstructured::new(&buf);
26595 Self::arbitrary(&mut unstructured).unwrap_or_default()
26596 }
26597}
26598impl Default for RADIO_STATUS_DATA {
26599 fn default() -> Self {
26600 Self::DEFAULT.clone()
26601 }
26602}
26603impl MessageData for RADIO_STATUS_DATA {
26604 type Message = MavMessage;
26605 const ID: u32 = 109u32;
26606 const NAME: &'static str = "RADIO_STATUS";
26607 const EXTRA_CRC: u8 = 185u8;
26608 const ENCODED_LEN: usize = 9usize;
26609 fn deser(
26610 _version: MavlinkVersion,
26611 __input: &[u8],
26612 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26613 let avail_len = __input.len();
26614 let mut payload_buf = [0; Self::ENCODED_LEN];
26615 let mut buf = if avail_len < Self::ENCODED_LEN {
26616 payload_buf[0..avail_len].copy_from_slice(__input);
26617 Bytes::new(&payload_buf)
26618 } else {
26619 Bytes::new(__input)
26620 };
26621 let mut __struct = Self::default();
26622 __struct.rxerrors = buf.get_u16_le()?;
26623 __struct.fixed = buf.get_u16_le()?;
26624 __struct.rssi = buf.get_u8()?;
26625 __struct.remrssi = buf.get_u8()?;
26626 __struct.txbuf = buf.get_u8()?;
26627 __struct.noise = buf.get_u8()?;
26628 __struct.remnoise = buf.get_u8()?;
26629 Ok(__struct)
26630 }
26631 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26632 let mut __tmp = BytesMut::new(bytes);
26633 #[allow(clippy::absurd_extreme_comparisons)]
26634 #[allow(unused_comparisons)]
26635 if __tmp.remaining() < Self::ENCODED_LEN {
26636 panic!(
26637 "buffer is too small (need {} bytes, but got {})",
26638 Self::ENCODED_LEN,
26639 __tmp.remaining(),
26640 )
26641 }
26642 __tmp.put_u16_le(self.rxerrors);
26643 __tmp.put_u16_le(self.fixed);
26644 __tmp.put_u8(self.rssi);
26645 __tmp.put_u8(self.remrssi);
26646 __tmp.put_u8(self.txbuf);
26647 __tmp.put_u8(self.noise);
26648 __tmp.put_u8(self.remnoise);
26649 if matches!(version, MavlinkVersion::V2) {
26650 let len = __tmp.len();
26651 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26652 } else {
26653 __tmp.len()
26654 }
26655 }
26656}
26657#[doc = "The RAW IMU readings for a 9DOF sensor, which is identified by the id (default IMU1). This message should always contain the true raw values without any scaling to allow data capture and system debugging."]
26658#[doc = ""]
26659#[doc = "ID: 27"]
26660#[derive(Debug, Clone, PartialEq)]
26661#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26662#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26663#[cfg_attr(feature = "ts", derive(TS))]
26664#[cfg_attr(feature = "ts", ts(export))]
26665pub struct RAW_IMU_DATA {
26666 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
26667 pub time_usec: u64,
26668 #[doc = "X acceleration (raw)"]
26669 pub xacc: i16,
26670 #[doc = "Y acceleration (raw)"]
26671 pub yacc: i16,
26672 #[doc = "Z acceleration (raw)"]
26673 pub zacc: i16,
26674 #[doc = "Angular speed around X axis (raw)"]
26675 pub xgyro: i16,
26676 #[doc = "Angular speed around Y axis (raw)"]
26677 pub ygyro: i16,
26678 #[doc = "Angular speed around Z axis (raw)"]
26679 pub zgyro: i16,
26680 #[doc = "X Magnetic field (raw)"]
26681 pub xmag: i16,
26682 #[doc = "Y Magnetic field (raw)"]
26683 pub ymag: i16,
26684 #[doc = "Z Magnetic field (raw)"]
26685 pub zmag: i16,
26686 #[doc = "Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)"]
26687 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26688 pub id: u8,
26689 #[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C)."]
26690 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26691 pub temperature: i16,
26692}
26693impl RAW_IMU_DATA {
26694 pub const ENCODED_LEN: usize = 29usize;
26695 pub const DEFAULT: Self = Self {
26696 time_usec: 0_u64,
26697 xacc: 0_i16,
26698 yacc: 0_i16,
26699 zacc: 0_i16,
26700 xgyro: 0_i16,
26701 ygyro: 0_i16,
26702 zgyro: 0_i16,
26703 xmag: 0_i16,
26704 ymag: 0_i16,
26705 zmag: 0_i16,
26706 id: 0_u8,
26707 temperature: 0_i16,
26708 };
26709 #[cfg(feature = "arbitrary")]
26710 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26711 use arbitrary::{Arbitrary, Unstructured};
26712 let mut buf = [0u8; 1024];
26713 rng.fill_bytes(&mut buf);
26714 let mut unstructured = Unstructured::new(&buf);
26715 Self::arbitrary(&mut unstructured).unwrap_or_default()
26716 }
26717}
26718impl Default for RAW_IMU_DATA {
26719 fn default() -> Self {
26720 Self::DEFAULT.clone()
26721 }
26722}
26723impl MessageData for RAW_IMU_DATA {
26724 type Message = MavMessage;
26725 const ID: u32 = 27u32;
26726 const NAME: &'static str = "RAW_IMU";
26727 const EXTRA_CRC: u8 = 144u8;
26728 const ENCODED_LEN: usize = 29usize;
26729 fn deser(
26730 _version: MavlinkVersion,
26731 __input: &[u8],
26732 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26733 let avail_len = __input.len();
26734 let mut payload_buf = [0; Self::ENCODED_LEN];
26735 let mut buf = if avail_len < Self::ENCODED_LEN {
26736 payload_buf[0..avail_len].copy_from_slice(__input);
26737 Bytes::new(&payload_buf)
26738 } else {
26739 Bytes::new(__input)
26740 };
26741 let mut __struct = Self::default();
26742 __struct.time_usec = buf.get_u64_le()?;
26743 __struct.xacc = buf.get_i16_le()?;
26744 __struct.yacc = buf.get_i16_le()?;
26745 __struct.zacc = buf.get_i16_le()?;
26746 __struct.xgyro = buf.get_i16_le()?;
26747 __struct.ygyro = buf.get_i16_le()?;
26748 __struct.zgyro = buf.get_i16_le()?;
26749 __struct.xmag = buf.get_i16_le()?;
26750 __struct.ymag = buf.get_i16_le()?;
26751 __struct.zmag = buf.get_i16_le()?;
26752 __struct.id = buf.get_u8()?;
26753 __struct.temperature = buf.get_i16_le()?;
26754 Ok(__struct)
26755 }
26756 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26757 let mut __tmp = BytesMut::new(bytes);
26758 #[allow(clippy::absurd_extreme_comparisons)]
26759 #[allow(unused_comparisons)]
26760 if __tmp.remaining() < Self::ENCODED_LEN {
26761 panic!(
26762 "buffer is too small (need {} bytes, but got {})",
26763 Self::ENCODED_LEN,
26764 __tmp.remaining(),
26765 )
26766 }
26767 __tmp.put_u64_le(self.time_usec);
26768 __tmp.put_i16_le(self.xacc);
26769 __tmp.put_i16_le(self.yacc);
26770 __tmp.put_i16_le(self.zacc);
26771 __tmp.put_i16_le(self.xgyro);
26772 __tmp.put_i16_le(self.ygyro);
26773 __tmp.put_i16_le(self.zgyro);
26774 __tmp.put_i16_le(self.xmag);
26775 __tmp.put_i16_le(self.ymag);
26776 __tmp.put_i16_le(self.zmag);
26777 if matches!(version, MavlinkVersion::V2) {
26778 __tmp.put_u8(self.id);
26779 __tmp.put_i16_le(self.temperature);
26780 let len = __tmp.len();
26781 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26782 } else {
26783 __tmp.len()
26784 }
26785 }
26786}
26787#[doc = "The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values."]
26788#[doc = ""]
26789#[doc = "ID: 28"]
26790#[derive(Debug, Clone, PartialEq)]
26791#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26792#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26793#[cfg_attr(feature = "ts", derive(TS))]
26794#[cfg_attr(feature = "ts", ts(export))]
26795pub struct RAW_PRESSURE_DATA {
26796 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
26797 pub time_usec: u64,
26798 #[doc = "Absolute pressure (raw)"]
26799 pub press_abs: i16,
26800 #[doc = "Differential pressure 1 (raw, 0 if nonexistent)"]
26801 pub press_diff1: i16,
26802 #[doc = "Differential pressure 2 (raw, 0 if nonexistent)"]
26803 pub press_diff2: i16,
26804 #[doc = "Raw Temperature measurement (raw)"]
26805 pub temperature: i16,
26806}
26807impl RAW_PRESSURE_DATA {
26808 pub const ENCODED_LEN: usize = 16usize;
26809 pub const DEFAULT: Self = Self {
26810 time_usec: 0_u64,
26811 press_abs: 0_i16,
26812 press_diff1: 0_i16,
26813 press_diff2: 0_i16,
26814 temperature: 0_i16,
26815 };
26816 #[cfg(feature = "arbitrary")]
26817 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26818 use arbitrary::{Arbitrary, Unstructured};
26819 let mut buf = [0u8; 1024];
26820 rng.fill_bytes(&mut buf);
26821 let mut unstructured = Unstructured::new(&buf);
26822 Self::arbitrary(&mut unstructured).unwrap_or_default()
26823 }
26824}
26825impl Default for RAW_PRESSURE_DATA {
26826 fn default() -> Self {
26827 Self::DEFAULT.clone()
26828 }
26829}
26830impl MessageData for RAW_PRESSURE_DATA {
26831 type Message = MavMessage;
26832 const ID: u32 = 28u32;
26833 const NAME: &'static str = "RAW_PRESSURE";
26834 const EXTRA_CRC: u8 = 67u8;
26835 const ENCODED_LEN: usize = 16usize;
26836 fn deser(
26837 _version: MavlinkVersion,
26838 __input: &[u8],
26839 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26840 let avail_len = __input.len();
26841 let mut payload_buf = [0; Self::ENCODED_LEN];
26842 let mut buf = if avail_len < Self::ENCODED_LEN {
26843 payload_buf[0..avail_len].copy_from_slice(__input);
26844 Bytes::new(&payload_buf)
26845 } else {
26846 Bytes::new(__input)
26847 };
26848 let mut __struct = Self::default();
26849 __struct.time_usec = buf.get_u64_le()?;
26850 __struct.press_abs = buf.get_i16_le()?;
26851 __struct.press_diff1 = buf.get_i16_le()?;
26852 __struct.press_diff2 = buf.get_i16_le()?;
26853 __struct.temperature = buf.get_i16_le()?;
26854 Ok(__struct)
26855 }
26856 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26857 let mut __tmp = BytesMut::new(bytes);
26858 #[allow(clippy::absurd_extreme_comparisons)]
26859 #[allow(unused_comparisons)]
26860 if __tmp.remaining() < Self::ENCODED_LEN {
26861 panic!(
26862 "buffer is too small (need {} bytes, but got {})",
26863 Self::ENCODED_LEN,
26864 __tmp.remaining(),
26865 )
26866 }
26867 __tmp.put_u64_le(self.time_usec);
26868 __tmp.put_i16_le(self.press_abs);
26869 __tmp.put_i16_le(self.press_diff1);
26870 __tmp.put_i16_le(self.press_diff2);
26871 __tmp.put_i16_le(self.temperature);
26872 if matches!(version, MavlinkVersion::V2) {
26873 let len = __tmp.len();
26874 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26875 } else {
26876 __tmp.len()
26877 }
26878 }
26879}
26880#[doc = "RPM sensor data message."]
26881#[doc = ""]
26882#[doc = "ID: 339"]
26883#[derive(Debug, Clone, PartialEq)]
26884#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26885#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26886#[cfg_attr(feature = "ts", derive(TS))]
26887#[cfg_attr(feature = "ts", ts(export))]
26888pub struct RAW_RPM_DATA {
26889 #[doc = "Indicated rate"]
26890 pub frequency: f32,
26891 #[doc = "Index of this RPM sensor (0-indexed)"]
26892 pub index: u8,
26893}
26894impl RAW_RPM_DATA {
26895 pub const ENCODED_LEN: usize = 5usize;
26896 pub const DEFAULT: Self = Self {
26897 frequency: 0.0_f32,
26898 index: 0_u8,
26899 };
26900 #[cfg(feature = "arbitrary")]
26901 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26902 use arbitrary::{Arbitrary, Unstructured};
26903 let mut buf = [0u8; 1024];
26904 rng.fill_bytes(&mut buf);
26905 let mut unstructured = Unstructured::new(&buf);
26906 Self::arbitrary(&mut unstructured).unwrap_or_default()
26907 }
26908}
26909impl Default for RAW_RPM_DATA {
26910 fn default() -> Self {
26911 Self::DEFAULT.clone()
26912 }
26913}
26914impl MessageData for RAW_RPM_DATA {
26915 type Message = MavMessage;
26916 const ID: u32 = 339u32;
26917 const NAME: &'static str = "RAW_RPM";
26918 const EXTRA_CRC: u8 = 199u8;
26919 const ENCODED_LEN: usize = 5usize;
26920 fn deser(
26921 _version: MavlinkVersion,
26922 __input: &[u8],
26923 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26924 let avail_len = __input.len();
26925 let mut payload_buf = [0; Self::ENCODED_LEN];
26926 let mut buf = if avail_len < Self::ENCODED_LEN {
26927 payload_buf[0..avail_len].copy_from_slice(__input);
26928 Bytes::new(&payload_buf)
26929 } else {
26930 Bytes::new(__input)
26931 };
26932 let mut __struct = Self::default();
26933 __struct.frequency = buf.get_f32_le()?;
26934 __struct.index = buf.get_u8()?;
26935 Ok(__struct)
26936 }
26937 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26938 let mut __tmp = BytesMut::new(bytes);
26939 #[allow(clippy::absurd_extreme_comparisons)]
26940 #[allow(unused_comparisons)]
26941 if __tmp.remaining() < Self::ENCODED_LEN {
26942 panic!(
26943 "buffer is too small (need {} bytes, but got {})",
26944 Self::ENCODED_LEN,
26945 __tmp.remaining(),
26946 )
26947 }
26948 __tmp.put_f32_le(self.frequency);
26949 __tmp.put_u8(self.index);
26950 if matches!(version, MavlinkVersion::V2) {
26951 let len = __tmp.len();
26952 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26953 } else {
26954 __tmp.len()
26955 }
26956 }
26957}
26958#[doc = "The PPM values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification."]
26959#[doc = ""]
26960#[doc = "ID: 65"]
26961#[derive(Debug, Clone, PartialEq)]
26962#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26963#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26964#[cfg_attr(feature = "ts", derive(TS))]
26965#[cfg_attr(feature = "ts", ts(export))]
26966pub struct RC_CHANNELS_DATA {
26967 #[doc = "Timestamp (time since system boot)."]
26968 pub time_boot_ms: u32,
26969 #[doc = "RC channel 1 value."]
26970 pub chan1_raw: u16,
26971 #[doc = "RC channel 2 value."]
26972 pub chan2_raw: u16,
26973 #[doc = "RC channel 3 value."]
26974 pub chan3_raw: u16,
26975 #[doc = "RC channel 4 value."]
26976 pub chan4_raw: u16,
26977 #[doc = "RC channel 5 value."]
26978 pub chan5_raw: u16,
26979 #[doc = "RC channel 6 value."]
26980 pub chan6_raw: u16,
26981 #[doc = "RC channel 7 value."]
26982 pub chan7_raw: u16,
26983 #[doc = "RC channel 8 value."]
26984 pub chan8_raw: u16,
26985 #[doc = "RC channel 9 value."]
26986 pub chan9_raw: u16,
26987 #[doc = "RC channel 10 value."]
26988 pub chan10_raw: u16,
26989 #[doc = "RC channel 11 value."]
26990 pub chan11_raw: u16,
26991 #[doc = "RC channel 12 value."]
26992 pub chan12_raw: u16,
26993 #[doc = "RC channel 13 value."]
26994 pub chan13_raw: u16,
26995 #[doc = "RC channel 14 value."]
26996 pub chan14_raw: u16,
26997 #[doc = "RC channel 15 value."]
26998 pub chan15_raw: u16,
26999 #[doc = "RC channel 16 value."]
27000 pub chan16_raw: u16,
27001 #[doc = "RC channel 17 value."]
27002 pub chan17_raw: u16,
27003 #[doc = "RC channel 18 value."]
27004 pub chan18_raw: u16,
27005 #[doc = "Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available."]
27006 pub chancount: u8,
27007 #[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
27008 pub rssi: u8,
27009}
27010impl RC_CHANNELS_DATA {
27011 pub const ENCODED_LEN: usize = 42usize;
27012 pub const DEFAULT: Self = Self {
27013 time_boot_ms: 0_u32,
27014 chan1_raw: 0_u16,
27015 chan2_raw: 0_u16,
27016 chan3_raw: 0_u16,
27017 chan4_raw: 0_u16,
27018 chan5_raw: 0_u16,
27019 chan6_raw: 0_u16,
27020 chan7_raw: 0_u16,
27021 chan8_raw: 0_u16,
27022 chan9_raw: 0_u16,
27023 chan10_raw: 0_u16,
27024 chan11_raw: 0_u16,
27025 chan12_raw: 0_u16,
27026 chan13_raw: 0_u16,
27027 chan14_raw: 0_u16,
27028 chan15_raw: 0_u16,
27029 chan16_raw: 0_u16,
27030 chan17_raw: 0_u16,
27031 chan18_raw: 0_u16,
27032 chancount: 0_u8,
27033 rssi: 0_u8,
27034 };
27035 #[cfg(feature = "arbitrary")]
27036 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27037 use arbitrary::{Arbitrary, Unstructured};
27038 let mut buf = [0u8; 1024];
27039 rng.fill_bytes(&mut buf);
27040 let mut unstructured = Unstructured::new(&buf);
27041 Self::arbitrary(&mut unstructured).unwrap_or_default()
27042 }
27043}
27044impl Default for RC_CHANNELS_DATA {
27045 fn default() -> Self {
27046 Self::DEFAULT.clone()
27047 }
27048}
27049impl MessageData for RC_CHANNELS_DATA {
27050 type Message = MavMessage;
27051 const ID: u32 = 65u32;
27052 const NAME: &'static str = "RC_CHANNELS";
27053 const EXTRA_CRC: u8 = 118u8;
27054 const ENCODED_LEN: usize = 42usize;
27055 fn deser(
27056 _version: MavlinkVersion,
27057 __input: &[u8],
27058 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27059 let avail_len = __input.len();
27060 let mut payload_buf = [0; Self::ENCODED_LEN];
27061 let mut buf = if avail_len < Self::ENCODED_LEN {
27062 payload_buf[0..avail_len].copy_from_slice(__input);
27063 Bytes::new(&payload_buf)
27064 } else {
27065 Bytes::new(__input)
27066 };
27067 let mut __struct = Self::default();
27068 __struct.time_boot_ms = buf.get_u32_le()?;
27069 __struct.chan1_raw = buf.get_u16_le()?;
27070 __struct.chan2_raw = buf.get_u16_le()?;
27071 __struct.chan3_raw = buf.get_u16_le()?;
27072 __struct.chan4_raw = buf.get_u16_le()?;
27073 __struct.chan5_raw = buf.get_u16_le()?;
27074 __struct.chan6_raw = buf.get_u16_le()?;
27075 __struct.chan7_raw = buf.get_u16_le()?;
27076 __struct.chan8_raw = buf.get_u16_le()?;
27077 __struct.chan9_raw = buf.get_u16_le()?;
27078 __struct.chan10_raw = buf.get_u16_le()?;
27079 __struct.chan11_raw = buf.get_u16_le()?;
27080 __struct.chan12_raw = buf.get_u16_le()?;
27081 __struct.chan13_raw = buf.get_u16_le()?;
27082 __struct.chan14_raw = buf.get_u16_le()?;
27083 __struct.chan15_raw = buf.get_u16_le()?;
27084 __struct.chan16_raw = buf.get_u16_le()?;
27085 __struct.chan17_raw = buf.get_u16_le()?;
27086 __struct.chan18_raw = buf.get_u16_le()?;
27087 __struct.chancount = buf.get_u8()?;
27088 __struct.rssi = buf.get_u8()?;
27089 Ok(__struct)
27090 }
27091 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27092 let mut __tmp = BytesMut::new(bytes);
27093 #[allow(clippy::absurd_extreme_comparisons)]
27094 #[allow(unused_comparisons)]
27095 if __tmp.remaining() < Self::ENCODED_LEN {
27096 panic!(
27097 "buffer is too small (need {} bytes, but got {})",
27098 Self::ENCODED_LEN,
27099 __tmp.remaining(),
27100 )
27101 }
27102 __tmp.put_u32_le(self.time_boot_ms);
27103 __tmp.put_u16_le(self.chan1_raw);
27104 __tmp.put_u16_le(self.chan2_raw);
27105 __tmp.put_u16_le(self.chan3_raw);
27106 __tmp.put_u16_le(self.chan4_raw);
27107 __tmp.put_u16_le(self.chan5_raw);
27108 __tmp.put_u16_le(self.chan6_raw);
27109 __tmp.put_u16_le(self.chan7_raw);
27110 __tmp.put_u16_le(self.chan8_raw);
27111 __tmp.put_u16_le(self.chan9_raw);
27112 __tmp.put_u16_le(self.chan10_raw);
27113 __tmp.put_u16_le(self.chan11_raw);
27114 __tmp.put_u16_le(self.chan12_raw);
27115 __tmp.put_u16_le(self.chan13_raw);
27116 __tmp.put_u16_le(self.chan14_raw);
27117 __tmp.put_u16_le(self.chan15_raw);
27118 __tmp.put_u16_le(self.chan16_raw);
27119 __tmp.put_u16_le(self.chan17_raw);
27120 __tmp.put_u16_le(self.chan18_raw);
27121 __tmp.put_u8(self.chancount);
27122 __tmp.put_u8(self.rssi);
27123 if matches!(version, MavlinkVersion::V2) {
27124 let len = __tmp.len();
27125 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27126 } else {
27127 __tmp.len()
27128 }
27129 }
27130}
27131#[doc = "The RAW values of the RC channels sent to the MAV to override info received from the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. Note carefully the semantic differences between the first 8 channels and the subsequent channels."]
27132#[doc = ""]
27133#[doc = "ID: 70"]
27134#[derive(Debug, Clone, PartialEq)]
27135#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27136#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27137#[cfg_attr(feature = "ts", derive(TS))]
27138#[cfg_attr(feature = "ts", ts(export))]
27139pub struct RC_CHANNELS_OVERRIDE_DATA {
27140 #[doc = "RC channel 1 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
27141 pub chan1_raw: u16,
27142 #[doc = "RC channel 2 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
27143 pub chan2_raw: u16,
27144 #[doc = "RC channel 3 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
27145 pub chan3_raw: u16,
27146 #[doc = "RC channel 4 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
27147 pub chan4_raw: u16,
27148 #[doc = "RC channel 5 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
27149 pub chan5_raw: u16,
27150 #[doc = "RC channel 6 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
27151 pub chan6_raw: u16,
27152 #[doc = "RC channel 7 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
27153 pub chan7_raw: u16,
27154 #[doc = "RC channel 8 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
27155 pub chan8_raw: u16,
27156 #[doc = "System ID"]
27157 pub target_system: u8,
27158 #[doc = "Component ID"]
27159 pub target_component: u8,
27160 #[doc = "RC channel 9 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
27161 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27162 pub chan9_raw: u16,
27163 #[doc = "RC channel 10 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
27164 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27165 pub chan10_raw: u16,
27166 #[doc = "RC channel 11 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
27167 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27168 pub chan11_raw: u16,
27169 #[doc = "RC channel 12 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
27170 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27171 pub chan12_raw: u16,
27172 #[doc = "RC channel 13 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
27173 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27174 pub chan13_raw: u16,
27175 #[doc = "RC channel 14 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
27176 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27177 pub chan14_raw: u16,
27178 #[doc = "RC channel 15 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
27179 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27180 pub chan15_raw: u16,
27181 #[doc = "RC channel 16 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
27182 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27183 pub chan16_raw: u16,
27184 #[doc = "RC channel 17 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
27185 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27186 pub chan17_raw: u16,
27187 #[doc = "RC channel 18 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
27188 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27189 pub chan18_raw: u16,
27190}
27191impl RC_CHANNELS_OVERRIDE_DATA {
27192 pub const ENCODED_LEN: usize = 38usize;
27193 pub const DEFAULT: Self = Self {
27194 chan1_raw: 0_u16,
27195 chan2_raw: 0_u16,
27196 chan3_raw: 0_u16,
27197 chan4_raw: 0_u16,
27198 chan5_raw: 0_u16,
27199 chan6_raw: 0_u16,
27200 chan7_raw: 0_u16,
27201 chan8_raw: 0_u16,
27202 target_system: 0_u8,
27203 target_component: 0_u8,
27204 chan9_raw: 0_u16,
27205 chan10_raw: 0_u16,
27206 chan11_raw: 0_u16,
27207 chan12_raw: 0_u16,
27208 chan13_raw: 0_u16,
27209 chan14_raw: 0_u16,
27210 chan15_raw: 0_u16,
27211 chan16_raw: 0_u16,
27212 chan17_raw: 0_u16,
27213 chan18_raw: 0_u16,
27214 };
27215 #[cfg(feature = "arbitrary")]
27216 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27217 use arbitrary::{Arbitrary, Unstructured};
27218 let mut buf = [0u8; 1024];
27219 rng.fill_bytes(&mut buf);
27220 let mut unstructured = Unstructured::new(&buf);
27221 Self::arbitrary(&mut unstructured).unwrap_or_default()
27222 }
27223}
27224impl Default for RC_CHANNELS_OVERRIDE_DATA {
27225 fn default() -> Self {
27226 Self::DEFAULT.clone()
27227 }
27228}
27229impl MessageData for RC_CHANNELS_OVERRIDE_DATA {
27230 type Message = MavMessage;
27231 const ID: u32 = 70u32;
27232 const NAME: &'static str = "RC_CHANNELS_OVERRIDE";
27233 const EXTRA_CRC: u8 = 124u8;
27234 const ENCODED_LEN: usize = 38usize;
27235 fn deser(
27236 _version: MavlinkVersion,
27237 __input: &[u8],
27238 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27239 let avail_len = __input.len();
27240 let mut payload_buf = [0; Self::ENCODED_LEN];
27241 let mut buf = if avail_len < Self::ENCODED_LEN {
27242 payload_buf[0..avail_len].copy_from_slice(__input);
27243 Bytes::new(&payload_buf)
27244 } else {
27245 Bytes::new(__input)
27246 };
27247 let mut __struct = Self::default();
27248 __struct.chan1_raw = buf.get_u16_le()?;
27249 __struct.chan2_raw = buf.get_u16_le()?;
27250 __struct.chan3_raw = buf.get_u16_le()?;
27251 __struct.chan4_raw = buf.get_u16_le()?;
27252 __struct.chan5_raw = buf.get_u16_le()?;
27253 __struct.chan6_raw = buf.get_u16_le()?;
27254 __struct.chan7_raw = buf.get_u16_le()?;
27255 __struct.chan8_raw = buf.get_u16_le()?;
27256 __struct.target_system = buf.get_u8()?;
27257 __struct.target_component = buf.get_u8()?;
27258 __struct.chan9_raw = buf.get_u16_le()?;
27259 __struct.chan10_raw = buf.get_u16_le()?;
27260 __struct.chan11_raw = buf.get_u16_le()?;
27261 __struct.chan12_raw = buf.get_u16_le()?;
27262 __struct.chan13_raw = buf.get_u16_le()?;
27263 __struct.chan14_raw = buf.get_u16_le()?;
27264 __struct.chan15_raw = buf.get_u16_le()?;
27265 __struct.chan16_raw = buf.get_u16_le()?;
27266 __struct.chan17_raw = buf.get_u16_le()?;
27267 __struct.chan18_raw = buf.get_u16_le()?;
27268 Ok(__struct)
27269 }
27270 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27271 let mut __tmp = BytesMut::new(bytes);
27272 #[allow(clippy::absurd_extreme_comparisons)]
27273 #[allow(unused_comparisons)]
27274 if __tmp.remaining() < Self::ENCODED_LEN {
27275 panic!(
27276 "buffer is too small (need {} bytes, but got {})",
27277 Self::ENCODED_LEN,
27278 __tmp.remaining(),
27279 )
27280 }
27281 __tmp.put_u16_le(self.chan1_raw);
27282 __tmp.put_u16_le(self.chan2_raw);
27283 __tmp.put_u16_le(self.chan3_raw);
27284 __tmp.put_u16_le(self.chan4_raw);
27285 __tmp.put_u16_le(self.chan5_raw);
27286 __tmp.put_u16_le(self.chan6_raw);
27287 __tmp.put_u16_le(self.chan7_raw);
27288 __tmp.put_u16_le(self.chan8_raw);
27289 __tmp.put_u8(self.target_system);
27290 __tmp.put_u8(self.target_component);
27291 if matches!(version, MavlinkVersion::V2) {
27292 __tmp.put_u16_le(self.chan9_raw);
27293 __tmp.put_u16_le(self.chan10_raw);
27294 __tmp.put_u16_le(self.chan11_raw);
27295 __tmp.put_u16_le(self.chan12_raw);
27296 __tmp.put_u16_le(self.chan13_raw);
27297 __tmp.put_u16_le(self.chan14_raw);
27298 __tmp.put_u16_le(self.chan15_raw);
27299 __tmp.put_u16_le(self.chan16_raw);
27300 __tmp.put_u16_le(self.chan17_raw);
27301 __tmp.put_u16_le(self.chan18_raw);
27302 let len = __tmp.len();
27303 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27304 } else {
27305 __tmp.len()
27306 }
27307 }
27308}
27309#[doc = "The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification."]
27310#[doc = ""]
27311#[doc = "ID: 35"]
27312#[derive(Debug, Clone, PartialEq)]
27313#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27314#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27315#[cfg_attr(feature = "ts", derive(TS))]
27316#[cfg_attr(feature = "ts", ts(export))]
27317pub struct RC_CHANNELS_RAW_DATA {
27318 #[doc = "Timestamp (time since system boot)."]
27319 pub time_boot_ms: u32,
27320 #[doc = "RC channel 1 value."]
27321 pub chan1_raw: u16,
27322 #[doc = "RC channel 2 value."]
27323 pub chan2_raw: u16,
27324 #[doc = "RC channel 3 value."]
27325 pub chan3_raw: u16,
27326 #[doc = "RC channel 4 value."]
27327 pub chan4_raw: u16,
27328 #[doc = "RC channel 5 value."]
27329 pub chan5_raw: u16,
27330 #[doc = "RC channel 6 value."]
27331 pub chan6_raw: u16,
27332 #[doc = "RC channel 7 value."]
27333 pub chan7_raw: u16,
27334 #[doc = "RC channel 8 value."]
27335 pub chan8_raw: u16,
27336 #[doc = "Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX."]
27337 pub port: u8,
27338 #[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
27339 pub rssi: u8,
27340}
27341impl RC_CHANNELS_RAW_DATA {
27342 pub const ENCODED_LEN: usize = 22usize;
27343 pub const DEFAULT: Self = Self {
27344 time_boot_ms: 0_u32,
27345 chan1_raw: 0_u16,
27346 chan2_raw: 0_u16,
27347 chan3_raw: 0_u16,
27348 chan4_raw: 0_u16,
27349 chan5_raw: 0_u16,
27350 chan6_raw: 0_u16,
27351 chan7_raw: 0_u16,
27352 chan8_raw: 0_u16,
27353 port: 0_u8,
27354 rssi: 0_u8,
27355 };
27356 #[cfg(feature = "arbitrary")]
27357 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27358 use arbitrary::{Arbitrary, Unstructured};
27359 let mut buf = [0u8; 1024];
27360 rng.fill_bytes(&mut buf);
27361 let mut unstructured = Unstructured::new(&buf);
27362 Self::arbitrary(&mut unstructured).unwrap_or_default()
27363 }
27364}
27365impl Default for RC_CHANNELS_RAW_DATA {
27366 fn default() -> Self {
27367 Self::DEFAULT.clone()
27368 }
27369}
27370impl MessageData for RC_CHANNELS_RAW_DATA {
27371 type Message = MavMessage;
27372 const ID: u32 = 35u32;
27373 const NAME: &'static str = "RC_CHANNELS_RAW";
27374 const EXTRA_CRC: u8 = 244u8;
27375 const ENCODED_LEN: usize = 22usize;
27376 fn deser(
27377 _version: MavlinkVersion,
27378 __input: &[u8],
27379 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27380 let avail_len = __input.len();
27381 let mut payload_buf = [0; Self::ENCODED_LEN];
27382 let mut buf = if avail_len < Self::ENCODED_LEN {
27383 payload_buf[0..avail_len].copy_from_slice(__input);
27384 Bytes::new(&payload_buf)
27385 } else {
27386 Bytes::new(__input)
27387 };
27388 let mut __struct = Self::default();
27389 __struct.time_boot_ms = buf.get_u32_le()?;
27390 __struct.chan1_raw = buf.get_u16_le()?;
27391 __struct.chan2_raw = buf.get_u16_le()?;
27392 __struct.chan3_raw = buf.get_u16_le()?;
27393 __struct.chan4_raw = buf.get_u16_le()?;
27394 __struct.chan5_raw = buf.get_u16_le()?;
27395 __struct.chan6_raw = buf.get_u16_le()?;
27396 __struct.chan7_raw = buf.get_u16_le()?;
27397 __struct.chan8_raw = buf.get_u16_le()?;
27398 __struct.port = buf.get_u8()?;
27399 __struct.rssi = buf.get_u8()?;
27400 Ok(__struct)
27401 }
27402 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27403 let mut __tmp = BytesMut::new(bytes);
27404 #[allow(clippy::absurd_extreme_comparisons)]
27405 #[allow(unused_comparisons)]
27406 if __tmp.remaining() < Self::ENCODED_LEN {
27407 panic!(
27408 "buffer is too small (need {} bytes, but got {})",
27409 Self::ENCODED_LEN,
27410 __tmp.remaining(),
27411 )
27412 }
27413 __tmp.put_u32_le(self.time_boot_ms);
27414 __tmp.put_u16_le(self.chan1_raw);
27415 __tmp.put_u16_le(self.chan2_raw);
27416 __tmp.put_u16_le(self.chan3_raw);
27417 __tmp.put_u16_le(self.chan4_raw);
27418 __tmp.put_u16_le(self.chan5_raw);
27419 __tmp.put_u16_le(self.chan6_raw);
27420 __tmp.put_u16_le(self.chan7_raw);
27421 __tmp.put_u16_le(self.chan8_raw);
27422 __tmp.put_u8(self.port);
27423 __tmp.put_u8(self.rssi);
27424 if matches!(version, MavlinkVersion::V2) {
27425 let len = __tmp.len();
27426 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27427 } else {
27428 __tmp.len()
27429 }
27430 }
27431}
27432#[doc = "The scaled values of the RC channels received: (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to INT16_MAX."]
27433#[doc = ""]
27434#[doc = "ID: 34"]
27435#[derive(Debug, Clone, PartialEq)]
27436#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27437#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27438#[cfg_attr(feature = "ts", derive(TS))]
27439#[cfg_attr(feature = "ts", ts(export))]
27440pub struct RC_CHANNELS_SCALED_DATA {
27441 #[doc = "Timestamp (time since system boot)."]
27442 pub time_boot_ms: u32,
27443 #[doc = "RC channel 1 value scaled."]
27444 pub chan1_scaled: i16,
27445 #[doc = "RC channel 2 value scaled."]
27446 pub chan2_scaled: i16,
27447 #[doc = "RC channel 3 value scaled."]
27448 pub chan3_scaled: i16,
27449 #[doc = "RC channel 4 value scaled."]
27450 pub chan4_scaled: i16,
27451 #[doc = "RC channel 5 value scaled."]
27452 pub chan5_scaled: i16,
27453 #[doc = "RC channel 6 value scaled."]
27454 pub chan6_scaled: i16,
27455 #[doc = "RC channel 7 value scaled."]
27456 pub chan7_scaled: i16,
27457 #[doc = "RC channel 8 value scaled."]
27458 pub chan8_scaled: i16,
27459 #[doc = "Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX."]
27460 pub port: u8,
27461 #[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
27462 pub rssi: u8,
27463}
27464impl RC_CHANNELS_SCALED_DATA {
27465 pub const ENCODED_LEN: usize = 22usize;
27466 pub const DEFAULT: Self = Self {
27467 time_boot_ms: 0_u32,
27468 chan1_scaled: 0_i16,
27469 chan2_scaled: 0_i16,
27470 chan3_scaled: 0_i16,
27471 chan4_scaled: 0_i16,
27472 chan5_scaled: 0_i16,
27473 chan6_scaled: 0_i16,
27474 chan7_scaled: 0_i16,
27475 chan8_scaled: 0_i16,
27476 port: 0_u8,
27477 rssi: 0_u8,
27478 };
27479 #[cfg(feature = "arbitrary")]
27480 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27481 use arbitrary::{Arbitrary, Unstructured};
27482 let mut buf = [0u8; 1024];
27483 rng.fill_bytes(&mut buf);
27484 let mut unstructured = Unstructured::new(&buf);
27485 Self::arbitrary(&mut unstructured).unwrap_or_default()
27486 }
27487}
27488impl Default for RC_CHANNELS_SCALED_DATA {
27489 fn default() -> Self {
27490 Self::DEFAULT.clone()
27491 }
27492}
27493impl MessageData for RC_CHANNELS_SCALED_DATA {
27494 type Message = MavMessage;
27495 const ID: u32 = 34u32;
27496 const NAME: &'static str = "RC_CHANNELS_SCALED";
27497 const EXTRA_CRC: u8 = 237u8;
27498 const ENCODED_LEN: usize = 22usize;
27499 fn deser(
27500 _version: MavlinkVersion,
27501 __input: &[u8],
27502 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27503 let avail_len = __input.len();
27504 let mut payload_buf = [0; Self::ENCODED_LEN];
27505 let mut buf = if avail_len < Self::ENCODED_LEN {
27506 payload_buf[0..avail_len].copy_from_slice(__input);
27507 Bytes::new(&payload_buf)
27508 } else {
27509 Bytes::new(__input)
27510 };
27511 let mut __struct = Self::default();
27512 __struct.time_boot_ms = buf.get_u32_le()?;
27513 __struct.chan1_scaled = buf.get_i16_le()?;
27514 __struct.chan2_scaled = buf.get_i16_le()?;
27515 __struct.chan3_scaled = buf.get_i16_le()?;
27516 __struct.chan4_scaled = buf.get_i16_le()?;
27517 __struct.chan5_scaled = buf.get_i16_le()?;
27518 __struct.chan6_scaled = buf.get_i16_le()?;
27519 __struct.chan7_scaled = buf.get_i16_le()?;
27520 __struct.chan8_scaled = buf.get_i16_le()?;
27521 __struct.port = buf.get_u8()?;
27522 __struct.rssi = buf.get_u8()?;
27523 Ok(__struct)
27524 }
27525 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27526 let mut __tmp = BytesMut::new(bytes);
27527 #[allow(clippy::absurd_extreme_comparisons)]
27528 #[allow(unused_comparisons)]
27529 if __tmp.remaining() < Self::ENCODED_LEN {
27530 panic!(
27531 "buffer is too small (need {} bytes, but got {})",
27532 Self::ENCODED_LEN,
27533 __tmp.remaining(),
27534 )
27535 }
27536 __tmp.put_u32_le(self.time_boot_ms);
27537 __tmp.put_i16_le(self.chan1_scaled);
27538 __tmp.put_i16_le(self.chan2_scaled);
27539 __tmp.put_i16_le(self.chan3_scaled);
27540 __tmp.put_i16_le(self.chan4_scaled);
27541 __tmp.put_i16_le(self.chan5_scaled);
27542 __tmp.put_i16_le(self.chan6_scaled);
27543 __tmp.put_i16_le(self.chan7_scaled);
27544 __tmp.put_i16_le(self.chan8_scaled);
27545 __tmp.put_u8(self.port);
27546 __tmp.put_u8(self.rssi);
27547 if matches!(version, MavlinkVersion::V2) {
27548 let len = __tmp.len();
27549 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27550 } else {
27551 __tmp.len()
27552 }
27553 }
27554}
27555#[deprecated = " See `MAV_CMD_SET_MESSAGE_INTERVAL ` (Deprecated since 2015-08)"]
27556#[doc = "Request a data stream."]
27557#[doc = ""]
27558#[doc = "ID: 66"]
27559#[derive(Debug, Clone, PartialEq)]
27560#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27561#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27562#[cfg_attr(feature = "ts", derive(TS))]
27563#[cfg_attr(feature = "ts", ts(export))]
27564pub struct REQUEST_DATA_STREAM_DATA {
27565 #[doc = "The requested message rate"]
27566 pub req_message_rate: u16,
27567 #[doc = "The target requested to send the message stream."]
27568 pub target_system: u8,
27569 #[doc = "The target requested to send the message stream."]
27570 pub target_component: u8,
27571 #[doc = "The ID of the requested data stream"]
27572 pub req_stream_id: u8,
27573 #[doc = "1 to start sending, 0 to stop sending."]
27574 pub start_stop: u8,
27575}
27576impl REQUEST_DATA_STREAM_DATA {
27577 pub const ENCODED_LEN: usize = 6usize;
27578 pub const DEFAULT: Self = Self {
27579 req_message_rate: 0_u16,
27580 target_system: 0_u8,
27581 target_component: 0_u8,
27582 req_stream_id: 0_u8,
27583 start_stop: 0_u8,
27584 };
27585 #[cfg(feature = "arbitrary")]
27586 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27587 use arbitrary::{Arbitrary, Unstructured};
27588 let mut buf = [0u8; 1024];
27589 rng.fill_bytes(&mut buf);
27590 let mut unstructured = Unstructured::new(&buf);
27591 Self::arbitrary(&mut unstructured).unwrap_or_default()
27592 }
27593}
27594impl Default for REQUEST_DATA_STREAM_DATA {
27595 fn default() -> Self {
27596 Self::DEFAULT.clone()
27597 }
27598}
27599impl MessageData for REQUEST_DATA_STREAM_DATA {
27600 type Message = MavMessage;
27601 const ID: u32 = 66u32;
27602 const NAME: &'static str = "REQUEST_DATA_STREAM";
27603 const EXTRA_CRC: u8 = 148u8;
27604 const ENCODED_LEN: usize = 6usize;
27605 fn deser(
27606 _version: MavlinkVersion,
27607 __input: &[u8],
27608 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27609 let avail_len = __input.len();
27610 let mut payload_buf = [0; Self::ENCODED_LEN];
27611 let mut buf = if avail_len < Self::ENCODED_LEN {
27612 payload_buf[0..avail_len].copy_from_slice(__input);
27613 Bytes::new(&payload_buf)
27614 } else {
27615 Bytes::new(__input)
27616 };
27617 let mut __struct = Self::default();
27618 __struct.req_message_rate = buf.get_u16_le()?;
27619 __struct.target_system = buf.get_u8()?;
27620 __struct.target_component = buf.get_u8()?;
27621 __struct.req_stream_id = buf.get_u8()?;
27622 __struct.start_stop = buf.get_u8()?;
27623 Ok(__struct)
27624 }
27625 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27626 let mut __tmp = BytesMut::new(bytes);
27627 #[allow(clippy::absurd_extreme_comparisons)]
27628 #[allow(unused_comparisons)]
27629 if __tmp.remaining() < Self::ENCODED_LEN {
27630 panic!(
27631 "buffer is too small (need {} bytes, but got {})",
27632 Self::ENCODED_LEN,
27633 __tmp.remaining(),
27634 )
27635 }
27636 __tmp.put_u16_le(self.req_message_rate);
27637 __tmp.put_u8(self.target_system);
27638 __tmp.put_u8(self.target_component);
27639 __tmp.put_u8(self.req_stream_id);
27640 __tmp.put_u8(self.start_stop);
27641 if matches!(version, MavlinkVersion::V2) {
27642 let len = __tmp.len();
27643 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27644 } else {
27645 __tmp.len()
27646 }
27647 }
27648}
27649#[doc = "Request one or more events to be (re-)sent. If first_sequence==last_sequence, only a single event is requested. Note that first_sequence can be larger than last_sequence (because the sequence number can wrap). Each sequence will trigger an EVENT or EVENT_ERROR response."]
27650#[doc = ""]
27651#[doc = "ID: 412"]
27652#[derive(Debug, Clone, PartialEq)]
27653#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27654#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27655#[cfg_attr(feature = "ts", derive(TS))]
27656#[cfg_attr(feature = "ts", ts(export))]
27657pub struct REQUEST_EVENT_DATA {
27658 #[doc = "First sequence number of the requested event."]
27659 pub first_sequence: u16,
27660 #[doc = "Last sequence number of the requested event."]
27661 pub last_sequence: u16,
27662 #[doc = "System ID"]
27663 pub target_system: u8,
27664 #[doc = "Component ID"]
27665 pub target_component: u8,
27666}
27667impl REQUEST_EVENT_DATA {
27668 pub const ENCODED_LEN: usize = 6usize;
27669 pub const DEFAULT: Self = Self {
27670 first_sequence: 0_u16,
27671 last_sequence: 0_u16,
27672 target_system: 0_u8,
27673 target_component: 0_u8,
27674 };
27675 #[cfg(feature = "arbitrary")]
27676 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27677 use arbitrary::{Arbitrary, Unstructured};
27678 let mut buf = [0u8; 1024];
27679 rng.fill_bytes(&mut buf);
27680 let mut unstructured = Unstructured::new(&buf);
27681 Self::arbitrary(&mut unstructured).unwrap_or_default()
27682 }
27683}
27684impl Default for REQUEST_EVENT_DATA {
27685 fn default() -> Self {
27686 Self::DEFAULT.clone()
27687 }
27688}
27689impl MessageData for REQUEST_EVENT_DATA {
27690 type Message = MavMessage;
27691 const ID: u32 = 412u32;
27692 const NAME: &'static str = "REQUEST_EVENT";
27693 const EXTRA_CRC: u8 = 33u8;
27694 const ENCODED_LEN: usize = 6usize;
27695 fn deser(
27696 _version: MavlinkVersion,
27697 __input: &[u8],
27698 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27699 let avail_len = __input.len();
27700 let mut payload_buf = [0; Self::ENCODED_LEN];
27701 let mut buf = if avail_len < Self::ENCODED_LEN {
27702 payload_buf[0..avail_len].copy_from_slice(__input);
27703 Bytes::new(&payload_buf)
27704 } else {
27705 Bytes::new(__input)
27706 };
27707 let mut __struct = Self::default();
27708 __struct.first_sequence = buf.get_u16_le()?;
27709 __struct.last_sequence = buf.get_u16_le()?;
27710 __struct.target_system = buf.get_u8()?;
27711 __struct.target_component = buf.get_u8()?;
27712 Ok(__struct)
27713 }
27714 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27715 let mut __tmp = BytesMut::new(bytes);
27716 #[allow(clippy::absurd_extreme_comparisons)]
27717 #[allow(unused_comparisons)]
27718 if __tmp.remaining() < Self::ENCODED_LEN {
27719 panic!(
27720 "buffer is too small (need {} bytes, but got {})",
27721 Self::ENCODED_LEN,
27722 __tmp.remaining(),
27723 )
27724 }
27725 __tmp.put_u16_le(self.first_sequence);
27726 __tmp.put_u16_le(self.last_sequence);
27727 __tmp.put_u8(self.target_system);
27728 __tmp.put_u8(self.target_component);
27729 if matches!(version, MavlinkVersion::V2) {
27730 let len = __tmp.len();
27731 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27732 } else {
27733 __tmp.len()
27734 }
27735 }
27736}
27737#[doc = "The autopilot is requesting a resource (file, binary, other type of data)."]
27738#[doc = ""]
27739#[doc = "ID: 142"]
27740#[derive(Debug, Clone, PartialEq)]
27741#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27742#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27743#[cfg_attr(feature = "ts", derive(TS))]
27744#[cfg_attr(feature = "ts", ts(export))]
27745pub struct RESOURCE_REQUEST_DATA {
27746 #[doc = "Request ID. This ID should be re-used when sending back URI contents"]
27747 pub request_id: u8,
27748 #[doc = "The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary"]
27749 pub uri_type: u8,
27750 #[doc = "The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum)"]
27751 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27752 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
27753 pub uri: [u8; 120],
27754 #[doc = "The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream."]
27755 pub transfer_type: u8,
27756 #[doc = "The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP)."]
27757 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27758 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
27759 pub storage: [u8; 120],
27760}
27761impl RESOURCE_REQUEST_DATA {
27762 pub const ENCODED_LEN: usize = 243usize;
27763 pub const DEFAULT: Self = Self {
27764 request_id: 0_u8,
27765 uri_type: 0_u8,
27766 uri: [0_u8; 120usize],
27767 transfer_type: 0_u8,
27768 storage: [0_u8; 120usize],
27769 };
27770 #[cfg(feature = "arbitrary")]
27771 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27772 use arbitrary::{Arbitrary, Unstructured};
27773 let mut buf = [0u8; 1024];
27774 rng.fill_bytes(&mut buf);
27775 let mut unstructured = Unstructured::new(&buf);
27776 Self::arbitrary(&mut unstructured).unwrap_or_default()
27777 }
27778}
27779impl Default for RESOURCE_REQUEST_DATA {
27780 fn default() -> Self {
27781 Self::DEFAULT.clone()
27782 }
27783}
27784impl MessageData for RESOURCE_REQUEST_DATA {
27785 type Message = MavMessage;
27786 const ID: u32 = 142u32;
27787 const NAME: &'static str = "RESOURCE_REQUEST";
27788 const EXTRA_CRC: u8 = 72u8;
27789 const ENCODED_LEN: usize = 243usize;
27790 fn deser(
27791 _version: MavlinkVersion,
27792 __input: &[u8],
27793 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27794 let avail_len = __input.len();
27795 let mut payload_buf = [0; Self::ENCODED_LEN];
27796 let mut buf = if avail_len < Self::ENCODED_LEN {
27797 payload_buf[0..avail_len].copy_from_slice(__input);
27798 Bytes::new(&payload_buf)
27799 } else {
27800 Bytes::new(__input)
27801 };
27802 let mut __struct = Self::default();
27803 __struct.request_id = buf.get_u8()?;
27804 __struct.uri_type = buf.get_u8()?;
27805 for v in &mut __struct.uri {
27806 let val = buf.get_u8()?;
27807 *v = val;
27808 }
27809 __struct.transfer_type = buf.get_u8()?;
27810 for v in &mut __struct.storage {
27811 let val = buf.get_u8()?;
27812 *v = val;
27813 }
27814 Ok(__struct)
27815 }
27816 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27817 let mut __tmp = BytesMut::new(bytes);
27818 #[allow(clippy::absurd_extreme_comparisons)]
27819 #[allow(unused_comparisons)]
27820 if __tmp.remaining() < Self::ENCODED_LEN {
27821 panic!(
27822 "buffer is too small (need {} bytes, but got {})",
27823 Self::ENCODED_LEN,
27824 __tmp.remaining(),
27825 )
27826 }
27827 __tmp.put_u8(self.request_id);
27828 __tmp.put_u8(self.uri_type);
27829 for val in &self.uri {
27830 __tmp.put_u8(*val);
27831 }
27832 __tmp.put_u8(self.transfer_type);
27833 for val in &self.storage {
27834 __tmp.put_u8(*val);
27835 }
27836 if matches!(version, MavlinkVersion::V2) {
27837 let len = __tmp.len();
27838 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27839 } else {
27840 __tmp.len()
27841 }
27842 }
27843}
27844#[doc = "Response to a REQUEST_EVENT in case of an error (e.g. the event is not available anymore)."]
27845#[doc = ""]
27846#[doc = "ID: 413"]
27847#[derive(Debug, Clone, PartialEq)]
27848#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27849#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27850#[cfg_attr(feature = "ts", derive(TS))]
27851#[cfg_attr(feature = "ts", ts(export))]
27852pub struct RESPONSE_EVENT_ERROR_DATA {
27853 #[doc = "Sequence number."]
27854 pub sequence: u16,
27855 #[doc = "Oldest Sequence number that is still available after the sequence set in REQUEST_EVENT."]
27856 pub sequence_oldest_available: u16,
27857 #[doc = "System ID"]
27858 pub target_system: u8,
27859 #[doc = "Component ID"]
27860 pub target_component: u8,
27861 #[doc = "Error reason."]
27862 pub reason: MavEventErrorReason,
27863}
27864impl RESPONSE_EVENT_ERROR_DATA {
27865 pub const ENCODED_LEN: usize = 7usize;
27866 pub const DEFAULT: Self = Self {
27867 sequence: 0_u16,
27868 sequence_oldest_available: 0_u16,
27869 target_system: 0_u8,
27870 target_component: 0_u8,
27871 reason: MavEventErrorReason::DEFAULT,
27872 };
27873 #[cfg(feature = "arbitrary")]
27874 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27875 use arbitrary::{Arbitrary, Unstructured};
27876 let mut buf = [0u8; 1024];
27877 rng.fill_bytes(&mut buf);
27878 let mut unstructured = Unstructured::new(&buf);
27879 Self::arbitrary(&mut unstructured).unwrap_or_default()
27880 }
27881}
27882impl Default for RESPONSE_EVENT_ERROR_DATA {
27883 fn default() -> Self {
27884 Self::DEFAULT.clone()
27885 }
27886}
27887impl MessageData for RESPONSE_EVENT_ERROR_DATA {
27888 type Message = MavMessage;
27889 const ID: u32 = 413u32;
27890 const NAME: &'static str = "RESPONSE_EVENT_ERROR";
27891 const EXTRA_CRC: u8 = 77u8;
27892 const ENCODED_LEN: usize = 7usize;
27893 fn deser(
27894 _version: MavlinkVersion,
27895 __input: &[u8],
27896 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27897 let avail_len = __input.len();
27898 let mut payload_buf = [0; Self::ENCODED_LEN];
27899 let mut buf = if avail_len < Self::ENCODED_LEN {
27900 payload_buf[0..avail_len].copy_from_slice(__input);
27901 Bytes::new(&payload_buf)
27902 } else {
27903 Bytes::new(__input)
27904 };
27905 let mut __struct = Self::default();
27906 __struct.sequence = buf.get_u16_le()?;
27907 __struct.sequence_oldest_available = buf.get_u16_le()?;
27908 __struct.target_system = buf.get_u8()?;
27909 __struct.target_component = buf.get_u8()?;
27910 let tmp = buf.get_u8()?;
27911 __struct.reason =
27912 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
27913 enum_type: "MavEventErrorReason",
27914 value: tmp as u64,
27915 })?;
27916 Ok(__struct)
27917 }
27918 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27919 let mut __tmp = BytesMut::new(bytes);
27920 #[allow(clippy::absurd_extreme_comparisons)]
27921 #[allow(unused_comparisons)]
27922 if __tmp.remaining() < Self::ENCODED_LEN {
27923 panic!(
27924 "buffer is too small (need {} bytes, but got {})",
27925 Self::ENCODED_LEN,
27926 __tmp.remaining(),
27927 )
27928 }
27929 __tmp.put_u16_le(self.sequence);
27930 __tmp.put_u16_le(self.sequence_oldest_available);
27931 __tmp.put_u8(self.target_system);
27932 __tmp.put_u8(self.target_component);
27933 __tmp.put_u8(self.reason as u8);
27934 if matches!(version, MavlinkVersion::V2) {
27935 let len = __tmp.len();
27936 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27937 } else {
27938 __tmp.len()
27939 }
27940 }
27941}
27942#[doc = "Read out the safety zone the MAV currently assumes."]
27943#[doc = ""]
27944#[doc = "ID: 55"]
27945#[derive(Debug, Clone, PartialEq)]
27946#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27947#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27948#[cfg_attr(feature = "ts", derive(TS))]
27949#[cfg_attr(feature = "ts", ts(export))]
27950pub struct SAFETY_ALLOWED_AREA_DATA {
27951 #[doc = "x position 1 / Latitude 1"]
27952 pub p1x: f32,
27953 #[doc = "y position 1 / Longitude 1"]
27954 pub p1y: f32,
27955 #[doc = "z position 1 / Altitude 1"]
27956 pub p1z: f32,
27957 #[doc = "x position 2 / Latitude 2"]
27958 pub p2x: f32,
27959 #[doc = "y position 2 / Longitude 2"]
27960 pub p2y: f32,
27961 #[doc = "z position 2 / Altitude 2"]
27962 pub p2z: f32,
27963 #[doc = "Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down."]
27964 pub frame: MavFrame,
27965}
27966impl SAFETY_ALLOWED_AREA_DATA {
27967 pub const ENCODED_LEN: usize = 25usize;
27968 pub const DEFAULT: Self = Self {
27969 p1x: 0.0_f32,
27970 p1y: 0.0_f32,
27971 p1z: 0.0_f32,
27972 p2x: 0.0_f32,
27973 p2y: 0.0_f32,
27974 p2z: 0.0_f32,
27975 frame: MavFrame::DEFAULT,
27976 };
27977 #[cfg(feature = "arbitrary")]
27978 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27979 use arbitrary::{Arbitrary, Unstructured};
27980 let mut buf = [0u8; 1024];
27981 rng.fill_bytes(&mut buf);
27982 let mut unstructured = Unstructured::new(&buf);
27983 Self::arbitrary(&mut unstructured).unwrap_or_default()
27984 }
27985}
27986impl Default for SAFETY_ALLOWED_AREA_DATA {
27987 fn default() -> Self {
27988 Self::DEFAULT.clone()
27989 }
27990}
27991impl MessageData for SAFETY_ALLOWED_AREA_DATA {
27992 type Message = MavMessage;
27993 const ID: u32 = 55u32;
27994 const NAME: &'static str = "SAFETY_ALLOWED_AREA";
27995 const EXTRA_CRC: u8 = 3u8;
27996 const ENCODED_LEN: usize = 25usize;
27997 fn deser(
27998 _version: MavlinkVersion,
27999 __input: &[u8],
28000 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28001 let avail_len = __input.len();
28002 let mut payload_buf = [0; Self::ENCODED_LEN];
28003 let mut buf = if avail_len < Self::ENCODED_LEN {
28004 payload_buf[0..avail_len].copy_from_slice(__input);
28005 Bytes::new(&payload_buf)
28006 } else {
28007 Bytes::new(__input)
28008 };
28009 let mut __struct = Self::default();
28010 __struct.p1x = buf.get_f32_le()?;
28011 __struct.p1y = buf.get_f32_le()?;
28012 __struct.p1z = buf.get_f32_le()?;
28013 __struct.p2x = buf.get_f32_le()?;
28014 __struct.p2y = buf.get_f32_le()?;
28015 __struct.p2z = buf.get_f32_le()?;
28016 let tmp = buf.get_u8()?;
28017 __struct.frame =
28018 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
28019 enum_type: "MavFrame",
28020 value: tmp as u64,
28021 })?;
28022 Ok(__struct)
28023 }
28024 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28025 let mut __tmp = BytesMut::new(bytes);
28026 #[allow(clippy::absurd_extreme_comparisons)]
28027 #[allow(unused_comparisons)]
28028 if __tmp.remaining() < Self::ENCODED_LEN {
28029 panic!(
28030 "buffer is too small (need {} bytes, but got {})",
28031 Self::ENCODED_LEN,
28032 __tmp.remaining(),
28033 )
28034 }
28035 __tmp.put_f32_le(self.p1x);
28036 __tmp.put_f32_le(self.p1y);
28037 __tmp.put_f32_le(self.p1z);
28038 __tmp.put_f32_le(self.p2x);
28039 __tmp.put_f32_le(self.p2y);
28040 __tmp.put_f32_le(self.p2z);
28041 __tmp.put_u8(self.frame as u8);
28042 if matches!(version, MavlinkVersion::V2) {
28043 let len = __tmp.len();
28044 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28045 } else {
28046 __tmp.len()
28047 }
28048 }
28049}
28050#[doc = "Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/waypoints to accept and which to reject. Safety areas are often enforced by national or competition regulations."]
28051#[doc = ""]
28052#[doc = "ID: 54"]
28053#[derive(Debug, Clone, PartialEq)]
28054#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28055#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28056#[cfg_attr(feature = "ts", derive(TS))]
28057#[cfg_attr(feature = "ts", ts(export))]
28058pub struct SAFETY_SET_ALLOWED_AREA_DATA {
28059 #[doc = "x position 1 / Latitude 1"]
28060 pub p1x: f32,
28061 #[doc = "y position 1 / Longitude 1"]
28062 pub p1y: f32,
28063 #[doc = "z position 1 / Altitude 1"]
28064 pub p1z: f32,
28065 #[doc = "x position 2 / Latitude 2"]
28066 pub p2x: f32,
28067 #[doc = "y position 2 / Longitude 2"]
28068 pub p2y: f32,
28069 #[doc = "z position 2 / Altitude 2"]
28070 pub p2z: f32,
28071 #[doc = "System ID"]
28072 pub target_system: u8,
28073 #[doc = "Component ID"]
28074 pub target_component: u8,
28075 #[doc = "Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down."]
28076 pub frame: MavFrame,
28077}
28078impl SAFETY_SET_ALLOWED_AREA_DATA {
28079 pub const ENCODED_LEN: usize = 27usize;
28080 pub const DEFAULT: Self = Self {
28081 p1x: 0.0_f32,
28082 p1y: 0.0_f32,
28083 p1z: 0.0_f32,
28084 p2x: 0.0_f32,
28085 p2y: 0.0_f32,
28086 p2z: 0.0_f32,
28087 target_system: 0_u8,
28088 target_component: 0_u8,
28089 frame: MavFrame::DEFAULT,
28090 };
28091 #[cfg(feature = "arbitrary")]
28092 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28093 use arbitrary::{Arbitrary, Unstructured};
28094 let mut buf = [0u8; 1024];
28095 rng.fill_bytes(&mut buf);
28096 let mut unstructured = Unstructured::new(&buf);
28097 Self::arbitrary(&mut unstructured).unwrap_or_default()
28098 }
28099}
28100impl Default for SAFETY_SET_ALLOWED_AREA_DATA {
28101 fn default() -> Self {
28102 Self::DEFAULT.clone()
28103 }
28104}
28105impl MessageData for SAFETY_SET_ALLOWED_AREA_DATA {
28106 type Message = MavMessage;
28107 const ID: u32 = 54u32;
28108 const NAME: &'static str = "SAFETY_SET_ALLOWED_AREA";
28109 const EXTRA_CRC: u8 = 15u8;
28110 const ENCODED_LEN: usize = 27usize;
28111 fn deser(
28112 _version: MavlinkVersion,
28113 __input: &[u8],
28114 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28115 let avail_len = __input.len();
28116 let mut payload_buf = [0; Self::ENCODED_LEN];
28117 let mut buf = if avail_len < Self::ENCODED_LEN {
28118 payload_buf[0..avail_len].copy_from_slice(__input);
28119 Bytes::new(&payload_buf)
28120 } else {
28121 Bytes::new(__input)
28122 };
28123 let mut __struct = Self::default();
28124 __struct.p1x = buf.get_f32_le()?;
28125 __struct.p1y = buf.get_f32_le()?;
28126 __struct.p1z = buf.get_f32_le()?;
28127 __struct.p2x = buf.get_f32_le()?;
28128 __struct.p2y = buf.get_f32_le()?;
28129 __struct.p2z = buf.get_f32_le()?;
28130 __struct.target_system = buf.get_u8()?;
28131 __struct.target_component = buf.get_u8()?;
28132 let tmp = buf.get_u8()?;
28133 __struct.frame =
28134 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
28135 enum_type: "MavFrame",
28136 value: tmp as u64,
28137 })?;
28138 Ok(__struct)
28139 }
28140 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28141 let mut __tmp = BytesMut::new(bytes);
28142 #[allow(clippy::absurd_extreme_comparisons)]
28143 #[allow(unused_comparisons)]
28144 if __tmp.remaining() < Self::ENCODED_LEN {
28145 panic!(
28146 "buffer is too small (need {} bytes, but got {})",
28147 Self::ENCODED_LEN,
28148 __tmp.remaining(),
28149 )
28150 }
28151 __tmp.put_f32_le(self.p1x);
28152 __tmp.put_f32_le(self.p1y);
28153 __tmp.put_f32_le(self.p1z);
28154 __tmp.put_f32_le(self.p2x);
28155 __tmp.put_f32_le(self.p2y);
28156 __tmp.put_f32_le(self.p2z);
28157 __tmp.put_u8(self.target_system);
28158 __tmp.put_u8(self.target_component);
28159 __tmp.put_u8(self.frame as u8);
28160 if matches!(version, MavlinkVersion::V2) {
28161 let len = __tmp.len();
28162 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28163 } else {
28164 __tmp.len()
28165 }
28166 }
28167}
28168#[doc = "The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units."]
28169#[doc = ""]
28170#[doc = "ID: 26"]
28171#[derive(Debug, Clone, PartialEq)]
28172#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28173#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28174#[cfg_attr(feature = "ts", derive(TS))]
28175#[cfg_attr(feature = "ts", ts(export))]
28176pub struct SCALED_IMU_DATA {
28177 #[doc = "Timestamp (time since system boot)."]
28178 pub time_boot_ms: u32,
28179 #[doc = "X acceleration"]
28180 pub xacc: i16,
28181 #[doc = "Y acceleration"]
28182 pub yacc: i16,
28183 #[doc = "Z acceleration"]
28184 pub zacc: i16,
28185 #[doc = "Angular speed around X axis"]
28186 pub xgyro: i16,
28187 #[doc = "Angular speed around Y axis"]
28188 pub ygyro: i16,
28189 #[doc = "Angular speed around Z axis"]
28190 pub zgyro: i16,
28191 #[doc = "X Magnetic field"]
28192 pub xmag: i16,
28193 #[doc = "Y Magnetic field"]
28194 pub ymag: i16,
28195 #[doc = "Z Magnetic field"]
28196 pub zmag: i16,
28197 #[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C)."]
28198 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28199 pub temperature: i16,
28200}
28201impl SCALED_IMU_DATA {
28202 pub const ENCODED_LEN: usize = 24usize;
28203 pub const DEFAULT: Self = Self {
28204 time_boot_ms: 0_u32,
28205 xacc: 0_i16,
28206 yacc: 0_i16,
28207 zacc: 0_i16,
28208 xgyro: 0_i16,
28209 ygyro: 0_i16,
28210 zgyro: 0_i16,
28211 xmag: 0_i16,
28212 ymag: 0_i16,
28213 zmag: 0_i16,
28214 temperature: 0_i16,
28215 };
28216 #[cfg(feature = "arbitrary")]
28217 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28218 use arbitrary::{Arbitrary, Unstructured};
28219 let mut buf = [0u8; 1024];
28220 rng.fill_bytes(&mut buf);
28221 let mut unstructured = Unstructured::new(&buf);
28222 Self::arbitrary(&mut unstructured).unwrap_or_default()
28223 }
28224}
28225impl Default for SCALED_IMU_DATA {
28226 fn default() -> Self {
28227 Self::DEFAULT.clone()
28228 }
28229}
28230impl MessageData for SCALED_IMU_DATA {
28231 type Message = MavMessage;
28232 const ID: u32 = 26u32;
28233 const NAME: &'static str = "SCALED_IMU";
28234 const EXTRA_CRC: u8 = 170u8;
28235 const ENCODED_LEN: usize = 24usize;
28236 fn deser(
28237 _version: MavlinkVersion,
28238 __input: &[u8],
28239 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28240 let avail_len = __input.len();
28241 let mut payload_buf = [0; Self::ENCODED_LEN];
28242 let mut buf = if avail_len < Self::ENCODED_LEN {
28243 payload_buf[0..avail_len].copy_from_slice(__input);
28244 Bytes::new(&payload_buf)
28245 } else {
28246 Bytes::new(__input)
28247 };
28248 let mut __struct = Self::default();
28249 __struct.time_boot_ms = buf.get_u32_le()?;
28250 __struct.xacc = buf.get_i16_le()?;
28251 __struct.yacc = buf.get_i16_le()?;
28252 __struct.zacc = buf.get_i16_le()?;
28253 __struct.xgyro = buf.get_i16_le()?;
28254 __struct.ygyro = buf.get_i16_le()?;
28255 __struct.zgyro = buf.get_i16_le()?;
28256 __struct.xmag = buf.get_i16_le()?;
28257 __struct.ymag = buf.get_i16_le()?;
28258 __struct.zmag = buf.get_i16_le()?;
28259 __struct.temperature = buf.get_i16_le()?;
28260 Ok(__struct)
28261 }
28262 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28263 let mut __tmp = BytesMut::new(bytes);
28264 #[allow(clippy::absurd_extreme_comparisons)]
28265 #[allow(unused_comparisons)]
28266 if __tmp.remaining() < Self::ENCODED_LEN {
28267 panic!(
28268 "buffer is too small (need {} bytes, but got {})",
28269 Self::ENCODED_LEN,
28270 __tmp.remaining(),
28271 )
28272 }
28273 __tmp.put_u32_le(self.time_boot_ms);
28274 __tmp.put_i16_le(self.xacc);
28275 __tmp.put_i16_le(self.yacc);
28276 __tmp.put_i16_le(self.zacc);
28277 __tmp.put_i16_le(self.xgyro);
28278 __tmp.put_i16_le(self.ygyro);
28279 __tmp.put_i16_le(self.zgyro);
28280 __tmp.put_i16_le(self.xmag);
28281 __tmp.put_i16_le(self.ymag);
28282 __tmp.put_i16_le(self.zmag);
28283 if matches!(version, MavlinkVersion::V2) {
28284 __tmp.put_i16_le(self.temperature);
28285 let len = __tmp.len();
28286 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28287 } else {
28288 __tmp.len()
28289 }
28290 }
28291}
28292#[doc = "The RAW IMU readings for secondary 9DOF sensor setup. This message should contain the scaled values to the described units."]
28293#[doc = ""]
28294#[doc = "ID: 116"]
28295#[derive(Debug, Clone, PartialEq)]
28296#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28297#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28298#[cfg_attr(feature = "ts", derive(TS))]
28299#[cfg_attr(feature = "ts", ts(export))]
28300pub struct SCALED_IMU2_DATA {
28301 #[doc = "Timestamp (time since system boot)."]
28302 pub time_boot_ms: u32,
28303 #[doc = "X acceleration"]
28304 pub xacc: i16,
28305 #[doc = "Y acceleration"]
28306 pub yacc: i16,
28307 #[doc = "Z acceleration"]
28308 pub zacc: i16,
28309 #[doc = "Angular speed around X axis"]
28310 pub xgyro: i16,
28311 #[doc = "Angular speed around Y axis"]
28312 pub ygyro: i16,
28313 #[doc = "Angular speed around Z axis"]
28314 pub zgyro: i16,
28315 #[doc = "X Magnetic field"]
28316 pub xmag: i16,
28317 #[doc = "Y Magnetic field"]
28318 pub ymag: i16,
28319 #[doc = "Z Magnetic field"]
28320 pub zmag: i16,
28321 #[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C)."]
28322 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28323 pub temperature: i16,
28324}
28325impl SCALED_IMU2_DATA {
28326 pub const ENCODED_LEN: usize = 24usize;
28327 pub const DEFAULT: Self = Self {
28328 time_boot_ms: 0_u32,
28329 xacc: 0_i16,
28330 yacc: 0_i16,
28331 zacc: 0_i16,
28332 xgyro: 0_i16,
28333 ygyro: 0_i16,
28334 zgyro: 0_i16,
28335 xmag: 0_i16,
28336 ymag: 0_i16,
28337 zmag: 0_i16,
28338 temperature: 0_i16,
28339 };
28340 #[cfg(feature = "arbitrary")]
28341 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28342 use arbitrary::{Arbitrary, Unstructured};
28343 let mut buf = [0u8; 1024];
28344 rng.fill_bytes(&mut buf);
28345 let mut unstructured = Unstructured::new(&buf);
28346 Self::arbitrary(&mut unstructured).unwrap_or_default()
28347 }
28348}
28349impl Default for SCALED_IMU2_DATA {
28350 fn default() -> Self {
28351 Self::DEFAULT.clone()
28352 }
28353}
28354impl MessageData for SCALED_IMU2_DATA {
28355 type Message = MavMessage;
28356 const ID: u32 = 116u32;
28357 const NAME: &'static str = "SCALED_IMU2";
28358 const EXTRA_CRC: u8 = 76u8;
28359 const ENCODED_LEN: usize = 24usize;
28360 fn deser(
28361 _version: MavlinkVersion,
28362 __input: &[u8],
28363 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28364 let avail_len = __input.len();
28365 let mut payload_buf = [0; Self::ENCODED_LEN];
28366 let mut buf = if avail_len < Self::ENCODED_LEN {
28367 payload_buf[0..avail_len].copy_from_slice(__input);
28368 Bytes::new(&payload_buf)
28369 } else {
28370 Bytes::new(__input)
28371 };
28372 let mut __struct = Self::default();
28373 __struct.time_boot_ms = buf.get_u32_le()?;
28374 __struct.xacc = buf.get_i16_le()?;
28375 __struct.yacc = buf.get_i16_le()?;
28376 __struct.zacc = buf.get_i16_le()?;
28377 __struct.xgyro = buf.get_i16_le()?;
28378 __struct.ygyro = buf.get_i16_le()?;
28379 __struct.zgyro = buf.get_i16_le()?;
28380 __struct.xmag = buf.get_i16_le()?;
28381 __struct.ymag = buf.get_i16_le()?;
28382 __struct.zmag = buf.get_i16_le()?;
28383 __struct.temperature = buf.get_i16_le()?;
28384 Ok(__struct)
28385 }
28386 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28387 let mut __tmp = BytesMut::new(bytes);
28388 #[allow(clippy::absurd_extreme_comparisons)]
28389 #[allow(unused_comparisons)]
28390 if __tmp.remaining() < Self::ENCODED_LEN {
28391 panic!(
28392 "buffer is too small (need {} bytes, but got {})",
28393 Self::ENCODED_LEN,
28394 __tmp.remaining(),
28395 )
28396 }
28397 __tmp.put_u32_le(self.time_boot_ms);
28398 __tmp.put_i16_le(self.xacc);
28399 __tmp.put_i16_le(self.yacc);
28400 __tmp.put_i16_le(self.zacc);
28401 __tmp.put_i16_le(self.xgyro);
28402 __tmp.put_i16_le(self.ygyro);
28403 __tmp.put_i16_le(self.zgyro);
28404 __tmp.put_i16_le(self.xmag);
28405 __tmp.put_i16_le(self.ymag);
28406 __tmp.put_i16_le(self.zmag);
28407 if matches!(version, MavlinkVersion::V2) {
28408 __tmp.put_i16_le(self.temperature);
28409 let len = __tmp.len();
28410 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28411 } else {
28412 __tmp.len()
28413 }
28414 }
28415}
28416#[doc = "The RAW IMU readings for 3rd 9DOF sensor setup. This message should contain the scaled values to the described units."]
28417#[doc = ""]
28418#[doc = "ID: 129"]
28419#[derive(Debug, Clone, PartialEq)]
28420#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28421#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28422#[cfg_attr(feature = "ts", derive(TS))]
28423#[cfg_attr(feature = "ts", ts(export))]
28424pub struct SCALED_IMU3_DATA {
28425 #[doc = "Timestamp (time since system boot)."]
28426 pub time_boot_ms: u32,
28427 #[doc = "X acceleration"]
28428 pub xacc: i16,
28429 #[doc = "Y acceleration"]
28430 pub yacc: i16,
28431 #[doc = "Z acceleration"]
28432 pub zacc: i16,
28433 #[doc = "Angular speed around X axis"]
28434 pub xgyro: i16,
28435 #[doc = "Angular speed around Y axis"]
28436 pub ygyro: i16,
28437 #[doc = "Angular speed around Z axis"]
28438 pub zgyro: i16,
28439 #[doc = "X Magnetic field"]
28440 pub xmag: i16,
28441 #[doc = "Y Magnetic field"]
28442 pub ymag: i16,
28443 #[doc = "Z Magnetic field"]
28444 pub zmag: i16,
28445 #[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C)."]
28446 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28447 pub temperature: i16,
28448}
28449impl SCALED_IMU3_DATA {
28450 pub const ENCODED_LEN: usize = 24usize;
28451 pub const DEFAULT: Self = Self {
28452 time_boot_ms: 0_u32,
28453 xacc: 0_i16,
28454 yacc: 0_i16,
28455 zacc: 0_i16,
28456 xgyro: 0_i16,
28457 ygyro: 0_i16,
28458 zgyro: 0_i16,
28459 xmag: 0_i16,
28460 ymag: 0_i16,
28461 zmag: 0_i16,
28462 temperature: 0_i16,
28463 };
28464 #[cfg(feature = "arbitrary")]
28465 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28466 use arbitrary::{Arbitrary, Unstructured};
28467 let mut buf = [0u8; 1024];
28468 rng.fill_bytes(&mut buf);
28469 let mut unstructured = Unstructured::new(&buf);
28470 Self::arbitrary(&mut unstructured).unwrap_or_default()
28471 }
28472}
28473impl Default for SCALED_IMU3_DATA {
28474 fn default() -> Self {
28475 Self::DEFAULT.clone()
28476 }
28477}
28478impl MessageData for SCALED_IMU3_DATA {
28479 type Message = MavMessage;
28480 const ID: u32 = 129u32;
28481 const NAME: &'static str = "SCALED_IMU3";
28482 const EXTRA_CRC: u8 = 46u8;
28483 const ENCODED_LEN: usize = 24usize;
28484 fn deser(
28485 _version: MavlinkVersion,
28486 __input: &[u8],
28487 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28488 let avail_len = __input.len();
28489 let mut payload_buf = [0; Self::ENCODED_LEN];
28490 let mut buf = if avail_len < Self::ENCODED_LEN {
28491 payload_buf[0..avail_len].copy_from_slice(__input);
28492 Bytes::new(&payload_buf)
28493 } else {
28494 Bytes::new(__input)
28495 };
28496 let mut __struct = Self::default();
28497 __struct.time_boot_ms = buf.get_u32_le()?;
28498 __struct.xacc = buf.get_i16_le()?;
28499 __struct.yacc = buf.get_i16_le()?;
28500 __struct.zacc = buf.get_i16_le()?;
28501 __struct.xgyro = buf.get_i16_le()?;
28502 __struct.ygyro = buf.get_i16_le()?;
28503 __struct.zgyro = buf.get_i16_le()?;
28504 __struct.xmag = buf.get_i16_le()?;
28505 __struct.ymag = buf.get_i16_le()?;
28506 __struct.zmag = buf.get_i16_le()?;
28507 __struct.temperature = buf.get_i16_le()?;
28508 Ok(__struct)
28509 }
28510 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28511 let mut __tmp = BytesMut::new(bytes);
28512 #[allow(clippy::absurd_extreme_comparisons)]
28513 #[allow(unused_comparisons)]
28514 if __tmp.remaining() < Self::ENCODED_LEN {
28515 panic!(
28516 "buffer is too small (need {} bytes, but got {})",
28517 Self::ENCODED_LEN,
28518 __tmp.remaining(),
28519 )
28520 }
28521 __tmp.put_u32_le(self.time_boot_ms);
28522 __tmp.put_i16_le(self.xacc);
28523 __tmp.put_i16_le(self.yacc);
28524 __tmp.put_i16_le(self.zacc);
28525 __tmp.put_i16_le(self.xgyro);
28526 __tmp.put_i16_le(self.ygyro);
28527 __tmp.put_i16_le(self.zgyro);
28528 __tmp.put_i16_le(self.xmag);
28529 __tmp.put_i16_le(self.ymag);
28530 __tmp.put_i16_le(self.zmag);
28531 if matches!(version, MavlinkVersion::V2) {
28532 __tmp.put_i16_le(self.temperature);
28533 let len = __tmp.len();
28534 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28535 } else {
28536 __tmp.len()
28537 }
28538 }
28539}
28540#[doc = "The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field."]
28541#[doc = ""]
28542#[doc = "ID: 29"]
28543#[derive(Debug, Clone, PartialEq)]
28544#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28545#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28546#[cfg_attr(feature = "ts", derive(TS))]
28547#[cfg_attr(feature = "ts", ts(export))]
28548pub struct SCALED_PRESSURE_DATA {
28549 #[doc = "Timestamp (time since system boot)."]
28550 pub time_boot_ms: u32,
28551 #[doc = "Absolute pressure"]
28552 pub press_abs: f32,
28553 #[doc = "Differential pressure 1"]
28554 pub press_diff: f32,
28555 #[doc = "Absolute pressure temperature"]
28556 pub temperature: i16,
28557 #[doc = "Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC."]
28558 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28559 pub temperature_press_diff: i16,
28560}
28561impl SCALED_PRESSURE_DATA {
28562 pub const ENCODED_LEN: usize = 16usize;
28563 pub const DEFAULT: Self = Self {
28564 time_boot_ms: 0_u32,
28565 press_abs: 0.0_f32,
28566 press_diff: 0.0_f32,
28567 temperature: 0_i16,
28568 temperature_press_diff: 0_i16,
28569 };
28570 #[cfg(feature = "arbitrary")]
28571 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28572 use arbitrary::{Arbitrary, Unstructured};
28573 let mut buf = [0u8; 1024];
28574 rng.fill_bytes(&mut buf);
28575 let mut unstructured = Unstructured::new(&buf);
28576 Self::arbitrary(&mut unstructured).unwrap_or_default()
28577 }
28578}
28579impl Default for SCALED_PRESSURE_DATA {
28580 fn default() -> Self {
28581 Self::DEFAULT.clone()
28582 }
28583}
28584impl MessageData for SCALED_PRESSURE_DATA {
28585 type Message = MavMessage;
28586 const ID: u32 = 29u32;
28587 const NAME: &'static str = "SCALED_PRESSURE";
28588 const EXTRA_CRC: u8 = 115u8;
28589 const ENCODED_LEN: usize = 16usize;
28590 fn deser(
28591 _version: MavlinkVersion,
28592 __input: &[u8],
28593 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28594 let avail_len = __input.len();
28595 let mut payload_buf = [0; Self::ENCODED_LEN];
28596 let mut buf = if avail_len < Self::ENCODED_LEN {
28597 payload_buf[0..avail_len].copy_from_slice(__input);
28598 Bytes::new(&payload_buf)
28599 } else {
28600 Bytes::new(__input)
28601 };
28602 let mut __struct = Self::default();
28603 __struct.time_boot_ms = buf.get_u32_le()?;
28604 __struct.press_abs = buf.get_f32_le()?;
28605 __struct.press_diff = buf.get_f32_le()?;
28606 __struct.temperature = buf.get_i16_le()?;
28607 __struct.temperature_press_diff = buf.get_i16_le()?;
28608 Ok(__struct)
28609 }
28610 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28611 let mut __tmp = BytesMut::new(bytes);
28612 #[allow(clippy::absurd_extreme_comparisons)]
28613 #[allow(unused_comparisons)]
28614 if __tmp.remaining() < Self::ENCODED_LEN {
28615 panic!(
28616 "buffer is too small (need {} bytes, but got {})",
28617 Self::ENCODED_LEN,
28618 __tmp.remaining(),
28619 )
28620 }
28621 __tmp.put_u32_le(self.time_boot_ms);
28622 __tmp.put_f32_le(self.press_abs);
28623 __tmp.put_f32_le(self.press_diff);
28624 __tmp.put_i16_le(self.temperature);
28625 if matches!(version, MavlinkVersion::V2) {
28626 __tmp.put_i16_le(self.temperature_press_diff);
28627 let len = __tmp.len();
28628 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28629 } else {
28630 __tmp.len()
28631 }
28632 }
28633}
28634#[doc = "Barometer readings for 2nd barometer."]
28635#[doc = ""]
28636#[doc = "ID: 137"]
28637#[derive(Debug, Clone, PartialEq)]
28638#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28639#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28640#[cfg_attr(feature = "ts", derive(TS))]
28641#[cfg_attr(feature = "ts", ts(export))]
28642pub struct SCALED_PRESSURE2_DATA {
28643 #[doc = "Timestamp (time since system boot)."]
28644 pub time_boot_ms: u32,
28645 #[doc = "Absolute pressure"]
28646 pub press_abs: f32,
28647 #[doc = "Differential pressure"]
28648 pub press_diff: f32,
28649 #[doc = "Absolute pressure temperature"]
28650 pub temperature: i16,
28651 #[doc = "Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC."]
28652 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28653 pub temperature_press_diff: i16,
28654}
28655impl SCALED_PRESSURE2_DATA {
28656 pub const ENCODED_LEN: usize = 16usize;
28657 pub const DEFAULT: Self = Self {
28658 time_boot_ms: 0_u32,
28659 press_abs: 0.0_f32,
28660 press_diff: 0.0_f32,
28661 temperature: 0_i16,
28662 temperature_press_diff: 0_i16,
28663 };
28664 #[cfg(feature = "arbitrary")]
28665 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28666 use arbitrary::{Arbitrary, Unstructured};
28667 let mut buf = [0u8; 1024];
28668 rng.fill_bytes(&mut buf);
28669 let mut unstructured = Unstructured::new(&buf);
28670 Self::arbitrary(&mut unstructured).unwrap_or_default()
28671 }
28672}
28673impl Default for SCALED_PRESSURE2_DATA {
28674 fn default() -> Self {
28675 Self::DEFAULT.clone()
28676 }
28677}
28678impl MessageData for SCALED_PRESSURE2_DATA {
28679 type Message = MavMessage;
28680 const ID: u32 = 137u32;
28681 const NAME: &'static str = "SCALED_PRESSURE2";
28682 const EXTRA_CRC: u8 = 195u8;
28683 const ENCODED_LEN: usize = 16usize;
28684 fn deser(
28685 _version: MavlinkVersion,
28686 __input: &[u8],
28687 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28688 let avail_len = __input.len();
28689 let mut payload_buf = [0; Self::ENCODED_LEN];
28690 let mut buf = if avail_len < Self::ENCODED_LEN {
28691 payload_buf[0..avail_len].copy_from_slice(__input);
28692 Bytes::new(&payload_buf)
28693 } else {
28694 Bytes::new(__input)
28695 };
28696 let mut __struct = Self::default();
28697 __struct.time_boot_ms = buf.get_u32_le()?;
28698 __struct.press_abs = buf.get_f32_le()?;
28699 __struct.press_diff = buf.get_f32_le()?;
28700 __struct.temperature = buf.get_i16_le()?;
28701 __struct.temperature_press_diff = buf.get_i16_le()?;
28702 Ok(__struct)
28703 }
28704 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28705 let mut __tmp = BytesMut::new(bytes);
28706 #[allow(clippy::absurd_extreme_comparisons)]
28707 #[allow(unused_comparisons)]
28708 if __tmp.remaining() < Self::ENCODED_LEN {
28709 panic!(
28710 "buffer is too small (need {} bytes, but got {})",
28711 Self::ENCODED_LEN,
28712 __tmp.remaining(),
28713 )
28714 }
28715 __tmp.put_u32_le(self.time_boot_ms);
28716 __tmp.put_f32_le(self.press_abs);
28717 __tmp.put_f32_le(self.press_diff);
28718 __tmp.put_i16_le(self.temperature);
28719 if matches!(version, MavlinkVersion::V2) {
28720 __tmp.put_i16_le(self.temperature_press_diff);
28721 let len = __tmp.len();
28722 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28723 } else {
28724 __tmp.len()
28725 }
28726 }
28727}
28728#[doc = "Barometer readings for 3rd barometer."]
28729#[doc = ""]
28730#[doc = "ID: 143"]
28731#[derive(Debug, Clone, PartialEq)]
28732#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28733#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28734#[cfg_attr(feature = "ts", derive(TS))]
28735#[cfg_attr(feature = "ts", ts(export))]
28736pub struct SCALED_PRESSURE3_DATA {
28737 #[doc = "Timestamp (time since system boot)."]
28738 pub time_boot_ms: u32,
28739 #[doc = "Absolute pressure"]
28740 pub press_abs: f32,
28741 #[doc = "Differential pressure"]
28742 pub press_diff: f32,
28743 #[doc = "Absolute pressure temperature"]
28744 pub temperature: i16,
28745 #[doc = "Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC."]
28746 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28747 pub temperature_press_diff: i16,
28748}
28749impl SCALED_PRESSURE3_DATA {
28750 pub const ENCODED_LEN: usize = 16usize;
28751 pub const DEFAULT: Self = Self {
28752 time_boot_ms: 0_u32,
28753 press_abs: 0.0_f32,
28754 press_diff: 0.0_f32,
28755 temperature: 0_i16,
28756 temperature_press_diff: 0_i16,
28757 };
28758 #[cfg(feature = "arbitrary")]
28759 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28760 use arbitrary::{Arbitrary, Unstructured};
28761 let mut buf = [0u8; 1024];
28762 rng.fill_bytes(&mut buf);
28763 let mut unstructured = Unstructured::new(&buf);
28764 Self::arbitrary(&mut unstructured).unwrap_or_default()
28765 }
28766}
28767impl Default for SCALED_PRESSURE3_DATA {
28768 fn default() -> Self {
28769 Self::DEFAULT.clone()
28770 }
28771}
28772impl MessageData for SCALED_PRESSURE3_DATA {
28773 type Message = MavMessage;
28774 const ID: u32 = 143u32;
28775 const NAME: &'static str = "SCALED_PRESSURE3";
28776 const EXTRA_CRC: u8 = 131u8;
28777 const ENCODED_LEN: usize = 16usize;
28778 fn deser(
28779 _version: MavlinkVersion,
28780 __input: &[u8],
28781 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28782 let avail_len = __input.len();
28783 let mut payload_buf = [0; Self::ENCODED_LEN];
28784 let mut buf = if avail_len < Self::ENCODED_LEN {
28785 payload_buf[0..avail_len].copy_from_slice(__input);
28786 Bytes::new(&payload_buf)
28787 } else {
28788 Bytes::new(__input)
28789 };
28790 let mut __struct = Self::default();
28791 __struct.time_boot_ms = buf.get_u32_le()?;
28792 __struct.press_abs = buf.get_f32_le()?;
28793 __struct.press_diff = buf.get_f32_le()?;
28794 __struct.temperature = buf.get_i16_le()?;
28795 __struct.temperature_press_diff = buf.get_i16_le()?;
28796 Ok(__struct)
28797 }
28798 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28799 let mut __tmp = BytesMut::new(bytes);
28800 #[allow(clippy::absurd_extreme_comparisons)]
28801 #[allow(unused_comparisons)]
28802 if __tmp.remaining() < Self::ENCODED_LEN {
28803 panic!(
28804 "buffer is too small (need {} bytes, but got {})",
28805 Self::ENCODED_LEN,
28806 __tmp.remaining(),
28807 )
28808 }
28809 __tmp.put_u32_le(self.time_boot_ms);
28810 __tmp.put_f32_le(self.press_abs);
28811 __tmp.put_f32_le(self.press_diff);
28812 __tmp.put_i16_le(self.temperature);
28813 if matches!(version, MavlinkVersion::V2) {
28814 __tmp.put_i16_le(self.temperature_press_diff);
28815 let len = __tmp.len();
28816 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28817 } else {
28818 __tmp.len()
28819 }
28820 }
28821}
28822#[doc = "Control a serial port. This can be used for raw access to an onboard serial peripheral such as a GPS or telemetry radio. It is designed to make it possible to update the devices firmware via MAVLink messages or change the devices settings. A message with zero bytes can be used to change just the baudrate."]
28823#[doc = ""]
28824#[doc = "ID: 126"]
28825#[derive(Debug, Clone, PartialEq)]
28826#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28827#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28828#[cfg_attr(feature = "ts", derive(TS))]
28829#[cfg_attr(feature = "ts", ts(export))]
28830pub struct SERIAL_CONTROL_DATA {
28831 #[doc = "Baudrate of transfer. Zero means no change."]
28832 pub baudrate: u32,
28833 #[doc = "Timeout for reply data"]
28834 pub timeout: u16,
28835 #[doc = "Serial control device type."]
28836 pub device: SerialControlDev,
28837 #[doc = "Bitmap of serial control flags."]
28838 pub flags: SerialControlFlag,
28839 #[doc = "how many bytes in this transfer"]
28840 pub count: u8,
28841 #[doc = "serial data"]
28842 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
28843 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
28844 pub data: [u8; 70],
28845 #[doc = "System ID"]
28846 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28847 pub target_system: u8,
28848 #[doc = "Component ID"]
28849 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28850 pub target_component: u8,
28851}
28852impl SERIAL_CONTROL_DATA {
28853 pub const ENCODED_LEN: usize = 81usize;
28854 pub const DEFAULT: Self = Self {
28855 baudrate: 0_u32,
28856 timeout: 0_u16,
28857 device: SerialControlDev::DEFAULT,
28858 flags: SerialControlFlag::DEFAULT,
28859 count: 0_u8,
28860 data: [0_u8; 70usize],
28861 target_system: 0_u8,
28862 target_component: 0_u8,
28863 };
28864 #[cfg(feature = "arbitrary")]
28865 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28866 use arbitrary::{Arbitrary, Unstructured};
28867 let mut buf = [0u8; 1024];
28868 rng.fill_bytes(&mut buf);
28869 let mut unstructured = Unstructured::new(&buf);
28870 Self::arbitrary(&mut unstructured).unwrap_or_default()
28871 }
28872}
28873impl Default for SERIAL_CONTROL_DATA {
28874 fn default() -> Self {
28875 Self::DEFAULT.clone()
28876 }
28877}
28878impl MessageData for SERIAL_CONTROL_DATA {
28879 type Message = MavMessage;
28880 const ID: u32 = 126u32;
28881 const NAME: &'static str = "SERIAL_CONTROL";
28882 const EXTRA_CRC: u8 = 220u8;
28883 const ENCODED_LEN: usize = 81usize;
28884 fn deser(
28885 _version: MavlinkVersion,
28886 __input: &[u8],
28887 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28888 let avail_len = __input.len();
28889 let mut payload_buf = [0; Self::ENCODED_LEN];
28890 let mut buf = if avail_len < Self::ENCODED_LEN {
28891 payload_buf[0..avail_len].copy_from_slice(__input);
28892 Bytes::new(&payload_buf)
28893 } else {
28894 Bytes::new(__input)
28895 };
28896 let mut __struct = Self::default();
28897 __struct.baudrate = buf.get_u32_le()?;
28898 __struct.timeout = buf.get_u16_le()?;
28899 let tmp = buf.get_u8()?;
28900 __struct.device =
28901 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
28902 enum_type: "SerialControlDev",
28903 value: tmp as u64,
28904 })?;
28905 let tmp = buf.get_u8()?;
28906 __struct.flags = SerialControlFlag::from_bits(tmp as <SerialControlFlag as Flags>::Bits)
28907 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
28908 flag_type: "SerialControlFlag",
28909 value: tmp as u64,
28910 })?;
28911 __struct.count = buf.get_u8()?;
28912 for v in &mut __struct.data {
28913 let val = buf.get_u8()?;
28914 *v = val;
28915 }
28916 __struct.target_system = buf.get_u8()?;
28917 __struct.target_component = buf.get_u8()?;
28918 Ok(__struct)
28919 }
28920 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28921 let mut __tmp = BytesMut::new(bytes);
28922 #[allow(clippy::absurd_extreme_comparisons)]
28923 #[allow(unused_comparisons)]
28924 if __tmp.remaining() < Self::ENCODED_LEN {
28925 panic!(
28926 "buffer is too small (need {} bytes, but got {})",
28927 Self::ENCODED_LEN,
28928 __tmp.remaining(),
28929 )
28930 }
28931 __tmp.put_u32_le(self.baudrate);
28932 __tmp.put_u16_le(self.timeout);
28933 __tmp.put_u8(self.device as u8);
28934 __tmp.put_u8(self.flags.bits() as u8);
28935 __tmp.put_u8(self.count);
28936 for val in &self.data {
28937 __tmp.put_u8(*val);
28938 }
28939 if matches!(version, MavlinkVersion::V2) {
28940 __tmp.put_u8(self.target_system);
28941 __tmp.put_u8(self.target_component);
28942 let len = __tmp.len();
28943 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28944 } else {
28945 __tmp.len()
28946 }
28947 }
28948}
28949#[doc = "Superseded by ACTUATOR_OUTPUT_STATUS. The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%."]
28950#[doc = ""]
28951#[doc = "ID: 36"]
28952#[derive(Debug, Clone, PartialEq)]
28953#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28954#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28955#[cfg_attr(feature = "ts", derive(TS))]
28956#[cfg_attr(feature = "ts", ts(export))]
28957pub struct SERVO_OUTPUT_RAW_DATA {
28958 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
28959 pub time_usec: u32,
28960 #[doc = "Servo output 1 value"]
28961 pub servo1_raw: u16,
28962 #[doc = "Servo output 2 value"]
28963 pub servo2_raw: u16,
28964 #[doc = "Servo output 3 value"]
28965 pub servo3_raw: u16,
28966 #[doc = "Servo output 4 value"]
28967 pub servo4_raw: u16,
28968 #[doc = "Servo output 5 value"]
28969 pub servo5_raw: u16,
28970 #[doc = "Servo output 6 value"]
28971 pub servo6_raw: u16,
28972 #[doc = "Servo output 7 value"]
28973 pub servo7_raw: u16,
28974 #[doc = "Servo output 8 value"]
28975 pub servo8_raw: u16,
28976 #[doc = "Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX."]
28977 pub port: u8,
28978 #[doc = "Servo output 9 value"]
28979 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28980 pub servo9_raw: u16,
28981 #[doc = "Servo output 10 value"]
28982 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28983 pub servo10_raw: u16,
28984 #[doc = "Servo output 11 value"]
28985 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28986 pub servo11_raw: u16,
28987 #[doc = "Servo output 12 value"]
28988 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28989 pub servo12_raw: u16,
28990 #[doc = "Servo output 13 value"]
28991 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28992 pub servo13_raw: u16,
28993 #[doc = "Servo output 14 value"]
28994 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28995 pub servo14_raw: u16,
28996 #[doc = "Servo output 15 value"]
28997 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28998 pub servo15_raw: u16,
28999 #[doc = "Servo output 16 value"]
29000 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29001 pub servo16_raw: u16,
29002}
29003impl SERVO_OUTPUT_RAW_DATA {
29004 pub const ENCODED_LEN: usize = 37usize;
29005 pub const DEFAULT: Self = Self {
29006 time_usec: 0_u32,
29007 servo1_raw: 0_u16,
29008 servo2_raw: 0_u16,
29009 servo3_raw: 0_u16,
29010 servo4_raw: 0_u16,
29011 servo5_raw: 0_u16,
29012 servo6_raw: 0_u16,
29013 servo7_raw: 0_u16,
29014 servo8_raw: 0_u16,
29015 port: 0_u8,
29016 servo9_raw: 0_u16,
29017 servo10_raw: 0_u16,
29018 servo11_raw: 0_u16,
29019 servo12_raw: 0_u16,
29020 servo13_raw: 0_u16,
29021 servo14_raw: 0_u16,
29022 servo15_raw: 0_u16,
29023 servo16_raw: 0_u16,
29024 };
29025 #[cfg(feature = "arbitrary")]
29026 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29027 use arbitrary::{Arbitrary, Unstructured};
29028 let mut buf = [0u8; 1024];
29029 rng.fill_bytes(&mut buf);
29030 let mut unstructured = Unstructured::new(&buf);
29031 Self::arbitrary(&mut unstructured).unwrap_or_default()
29032 }
29033}
29034impl Default for SERVO_OUTPUT_RAW_DATA {
29035 fn default() -> Self {
29036 Self::DEFAULT.clone()
29037 }
29038}
29039impl MessageData for SERVO_OUTPUT_RAW_DATA {
29040 type Message = MavMessage;
29041 const ID: u32 = 36u32;
29042 const NAME: &'static str = "SERVO_OUTPUT_RAW";
29043 const EXTRA_CRC: u8 = 222u8;
29044 const ENCODED_LEN: usize = 37usize;
29045 fn deser(
29046 _version: MavlinkVersion,
29047 __input: &[u8],
29048 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29049 let avail_len = __input.len();
29050 let mut payload_buf = [0; Self::ENCODED_LEN];
29051 let mut buf = if avail_len < Self::ENCODED_LEN {
29052 payload_buf[0..avail_len].copy_from_slice(__input);
29053 Bytes::new(&payload_buf)
29054 } else {
29055 Bytes::new(__input)
29056 };
29057 let mut __struct = Self::default();
29058 __struct.time_usec = buf.get_u32_le()?;
29059 __struct.servo1_raw = buf.get_u16_le()?;
29060 __struct.servo2_raw = buf.get_u16_le()?;
29061 __struct.servo3_raw = buf.get_u16_le()?;
29062 __struct.servo4_raw = buf.get_u16_le()?;
29063 __struct.servo5_raw = buf.get_u16_le()?;
29064 __struct.servo6_raw = buf.get_u16_le()?;
29065 __struct.servo7_raw = buf.get_u16_le()?;
29066 __struct.servo8_raw = buf.get_u16_le()?;
29067 __struct.port = buf.get_u8()?;
29068 __struct.servo9_raw = buf.get_u16_le()?;
29069 __struct.servo10_raw = buf.get_u16_le()?;
29070 __struct.servo11_raw = buf.get_u16_le()?;
29071 __struct.servo12_raw = buf.get_u16_le()?;
29072 __struct.servo13_raw = buf.get_u16_le()?;
29073 __struct.servo14_raw = buf.get_u16_le()?;
29074 __struct.servo15_raw = buf.get_u16_le()?;
29075 __struct.servo16_raw = buf.get_u16_le()?;
29076 Ok(__struct)
29077 }
29078 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29079 let mut __tmp = BytesMut::new(bytes);
29080 #[allow(clippy::absurd_extreme_comparisons)]
29081 #[allow(unused_comparisons)]
29082 if __tmp.remaining() < Self::ENCODED_LEN {
29083 panic!(
29084 "buffer is too small (need {} bytes, but got {})",
29085 Self::ENCODED_LEN,
29086 __tmp.remaining(),
29087 )
29088 }
29089 __tmp.put_u32_le(self.time_usec);
29090 __tmp.put_u16_le(self.servo1_raw);
29091 __tmp.put_u16_le(self.servo2_raw);
29092 __tmp.put_u16_le(self.servo3_raw);
29093 __tmp.put_u16_le(self.servo4_raw);
29094 __tmp.put_u16_le(self.servo5_raw);
29095 __tmp.put_u16_le(self.servo6_raw);
29096 __tmp.put_u16_le(self.servo7_raw);
29097 __tmp.put_u16_le(self.servo8_raw);
29098 __tmp.put_u8(self.port);
29099 if matches!(version, MavlinkVersion::V2) {
29100 __tmp.put_u16_le(self.servo9_raw);
29101 __tmp.put_u16_le(self.servo10_raw);
29102 __tmp.put_u16_le(self.servo11_raw);
29103 __tmp.put_u16_le(self.servo12_raw);
29104 __tmp.put_u16_le(self.servo13_raw);
29105 __tmp.put_u16_le(self.servo14_raw);
29106 __tmp.put_u16_le(self.servo15_raw);
29107 __tmp.put_u16_le(self.servo16_raw);
29108 let len = __tmp.len();
29109 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29110 } else {
29111 __tmp.len()
29112 }
29113 }
29114}
29115#[doc = "Setup a MAVLink2 signing key. If called with secret_key of all zero and zero initial_timestamp will disable signing."]
29116#[doc = ""]
29117#[doc = "ID: 256"]
29118#[derive(Debug, Clone, PartialEq)]
29119#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29120#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29121#[cfg_attr(feature = "ts", derive(TS))]
29122#[cfg_attr(feature = "ts", ts(export))]
29123pub struct SETUP_SIGNING_DATA {
29124 #[doc = "initial timestamp"]
29125 pub initial_timestamp: u64,
29126 #[doc = "system id of the target"]
29127 pub target_system: u8,
29128 #[doc = "component ID of the target"]
29129 pub target_component: u8,
29130 #[doc = "signing key"]
29131 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29132 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
29133 pub secret_key: [u8; 32],
29134}
29135impl SETUP_SIGNING_DATA {
29136 pub const ENCODED_LEN: usize = 42usize;
29137 pub const DEFAULT: Self = Self {
29138 initial_timestamp: 0_u64,
29139 target_system: 0_u8,
29140 target_component: 0_u8,
29141 secret_key: [0_u8; 32usize],
29142 };
29143 #[cfg(feature = "arbitrary")]
29144 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29145 use arbitrary::{Arbitrary, Unstructured};
29146 let mut buf = [0u8; 1024];
29147 rng.fill_bytes(&mut buf);
29148 let mut unstructured = Unstructured::new(&buf);
29149 Self::arbitrary(&mut unstructured).unwrap_or_default()
29150 }
29151}
29152impl Default for SETUP_SIGNING_DATA {
29153 fn default() -> Self {
29154 Self::DEFAULT.clone()
29155 }
29156}
29157impl MessageData for SETUP_SIGNING_DATA {
29158 type Message = MavMessage;
29159 const ID: u32 = 256u32;
29160 const NAME: &'static str = "SETUP_SIGNING";
29161 const EXTRA_CRC: u8 = 71u8;
29162 const ENCODED_LEN: usize = 42usize;
29163 fn deser(
29164 _version: MavlinkVersion,
29165 __input: &[u8],
29166 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29167 let avail_len = __input.len();
29168 let mut payload_buf = [0; Self::ENCODED_LEN];
29169 let mut buf = if avail_len < Self::ENCODED_LEN {
29170 payload_buf[0..avail_len].copy_from_slice(__input);
29171 Bytes::new(&payload_buf)
29172 } else {
29173 Bytes::new(__input)
29174 };
29175 let mut __struct = Self::default();
29176 __struct.initial_timestamp = buf.get_u64_le()?;
29177 __struct.target_system = buf.get_u8()?;
29178 __struct.target_component = buf.get_u8()?;
29179 for v in &mut __struct.secret_key {
29180 let val = buf.get_u8()?;
29181 *v = val;
29182 }
29183 Ok(__struct)
29184 }
29185 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29186 let mut __tmp = BytesMut::new(bytes);
29187 #[allow(clippy::absurd_extreme_comparisons)]
29188 #[allow(unused_comparisons)]
29189 if __tmp.remaining() < Self::ENCODED_LEN {
29190 panic!(
29191 "buffer is too small (need {} bytes, but got {})",
29192 Self::ENCODED_LEN,
29193 __tmp.remaining(),
29194 )
29195 }
29196 __tmp.put_u64_le(self.initial_timestamp);
29197 __tmp.put_u8(self.target_system);
29198 __tmp.put_u8(self.target_component);
29199 for val in &self.secret_key {
29200 __tmp.put_u8(*val);
29201 }
29202 if matches!(version, MavlinkVersion::V2) {
29203 let len = __tmp.len();
29204 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29205 } else {
29206 __tmp.len()
29207 }
29208 }
29209}
29210#[doc = "Set the vehicle attitude and body angular rates."]
29211#[doc = ""]
29212#[doc = "ID: 139"]
29213#[derive(Debug, Clone, PartialEq)]
29214#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29215#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29216#[cfg_attr(feature = "ts", derive(TS))]
29217#[cfg_attr(feature = "ts", ts(export))]
29218pub struct SET_ACTUATOR_CONTROL_TARGET_DATA {
29219 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
29220 pub time_usec: u64,
29221 #[doc = "Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs."]
29222 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29223 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
29224 pub controls: [f32; 8],
29225 #[doc = "Actuator group. The \"_mlx\" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances."]
29226 pub group_mlx: u8,
29227 #[doc = "System ID"]
29228 pub target_system: u8,
29229 #[doc = "Component ID"]
29230 pub target_component: u8,
29231}
29232impl SET_ACTUATOR_CONTROL_TARGET_DATA {
29233 pub const ENCODED_LEN: usize = 43usize;
29234 pub const DEFAULT: Self = Self {
29235 time_usec: 0_u64,
29236 controls: [0.0_f32; 8usize],
29237 group_mlx: 0_u8,
29238 target_system: 0_u8,
29239 target_component: 0_u8,
29240 };
29241 #[cfg(feature = "arbitrary")]
29242 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29243 use arbitrary::{Arbitrary, Unstructured};
29244 let mut buf = [0u8; 1024];
29245 rng.fill_bytes(&mut buf);
29246 let mut unstructured = Unstructured::new(&buf);
29247 Self::arbitrary(&mut unstructured).unwrap_or_default()
29248 }
29249}
29250impl Default for SET_ACTUATOR_CONTROL_TARGET_DATA {
29251 fn default() -> Self {
29252 Self::DEFAULT.clone()
29253 }
29254}
29255impl MessageData for SET_ACTUATOR_CONTROL_TARGET_DATA {
29256 type Message = MavMessage;
29257 const ID: u32 = 139u32;
29258 const NAME: &'static str = "SET_ACTUATOR_CONTROL_TARGET";
29259 const EXTRA_CRC: u8 = 168u8;
29260 const ENCODED_LEN: usize = 43usize;
29261 fn deser(
29262 _version: MavlinkVersion,
29263 __input: &[u8],
29264 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29265 let avail_len = __input.len();
29266 let mut payload_buf = [0; Self::ENCODED_LEN];
29267 let mut buf = if avail_len < Self::ENCODED_LEN {
29268 payload_buf[0..avail_len].copy_from_slice(__input);
29269 Bytes::new(&payload_buf)
29270 } else {
29271 Bytes::new(__input)
29272 };
29273 let mut __struct = Self::default();
29274 __struct.time_usec = buf.get_u64_le()?;
29275 for v in &mut __struct.controls {
29276 let val = buf.get_f32_le()?;
29277 *v = val;
29278 }
29279 __struct.group_mlx = buf.get_u8()?;
29280 __struct.target_system = buf.get_u8()?;
29281 __struct.target_component = buf.get_u8()?;
29282 Ok(__struct)
29283 }
29284 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29285 let mut __tmp = BytesMut::new(bytes);
29286 #[allow(clippy::absurd_extreme_comparisons)]
29287 #[allow(unused_comparisons)]
29288 if __tmp.remaining() < Self::ENCODED_LEN {
29289 panic!(
29290 "buffer is too small (need {} bytes, but got {})",
29291 Self::ENCODED_LEN,
29292 __tmp.remaining(),
29293 )
29294 }
29295 __tmp.put_u64_le(self.time_usec);
29296 for val in &self.controls {
29297 __tmp.put_f32_le(*val);
29298 }
29299 __tmp.put_u8(self.group_mlx);
29300 __tmp.put_u8(self.target_system);
29301 __tmp.put_u8(self.target_component);
29302 if matches!(version, MavlinkVersion::V2) {
29303 let len = __tmp.len();
29304 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29305 } else {
29306 __tmp.len()
29307 }
29308 }
29309}
29310#[doc = "Sets a desired vehicle attitude. Used by an external controller to command the vehicle (manual controller or other system)."]
29311#[doc = ""]
29312#[doc = "ID: 82"]
29313#[derive(Debug, Clone, PartialEq)]
29314#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29315#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29316#[cfg_attr(feature = "ts", derive(TS))]
29317#[cfg_attr(feature = "ts", ts(export))]
29318pub struct SET_ATTITUDE_TARGET_DATA {
29319 #[doc = "Timestamp (time since system boot)."]
29320 pub time_boot_ms: u32,
29321 #[doc = "Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) from MAV_FRAME_LOCAL_NED to MAV_FRAME_BODY_FRD"]
29322 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29323 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
29324 pub q: [f32; 4],
29325 #[doc = "Body roll rate"]
29326 pub body_roll_rate: f32,
29327 #[doc = "Body pitch rate"]
29328 pub body_pitch_rate: f32,
29329 #[doc = "Body yaw rate"]
29330 pub body_yaw_rate: f32,
29331 #[doc = "Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)"]
29332 pub thrust: f32,
29333 #[doc = "System ID"]
29334 pub target_system: u8,
29335 #[doc = "Component ID"]
29336 pub target_component: u8,
29337 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
29338 pub type_mask: AttitudeTargetTypemask,
29339 #[doc = "3D thrust setpoint in the body NED frame, normalized to -1 .. 1"]
29340 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29341 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29342 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
29343 pub thrust_body: [f32; 3],
29344}
29345impl SET_ATTITUDE_TARGET_DATA {
29346 pub const ENCODED_LEN: usize = 51usize;
29347 pub const DEFAULT: Self = Self {
29348 time_boot_ms: 0_u32,
29349 q: [0.0_f32; 4usize],
29350 body_roll_rate: 0.0_f32,
29351 body_pitch_rate: 0.0_f32,
29352 body_yaw_rate: 0.0_f32,
29353 thrust: 0.0_f32,
29354 target_system: 0_u8,
29355 target_component: 0_u8,
29356 type_mask: AttitudeTargetTypemask::DEFAULT,
29357 thrust_body: [0.0_f32; 3usize],
29358 };
29359 #[cfg(feature = "arbitrary")]
29360 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29361 use arbitrary::{Arbitrary, Unstructured};
29362 let mut buf = [0u8; 1024];
29363 rng.fill_bytes(&mut buf);
29364 let mut unstructured = Unstructured::new(&buf);
29365 Self::arbitrary(&mut unstructured).unwrap_or_default()
29366 }
29367}
29368impl Default for SET_ATTITUDE_TARGET_DATA {
29369 fn default() -> Self {
29370 Self::DEFAULT.clone()
29371 }
29372}
29373impl MessageData for SET_ATTITUDE_TARGET_DATA {
29374 type Message = MavMessage;
29375 const ID: u32 = 82u32;
29376 const NAME: &'static str = "SET_ATTITUDE_TARGET";
29377 const EXTRA_CRC: u8 = 49u8;
29378 const ENCODED_LEN: usize = 51usize;
29379 fn deser(
29380 _version: MavlinkVersion,
29381 __input: &[u8],
29382 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29383 let avail_len = __input.len();
29384 let mut payload_buf = [0; Self::ENCODED_LEN];
29385 let mut buf = if avail_len < Self::ENCODED_LEN {
29386 payload_buf[0..avail_len].copy_from_slice(__input);
29387 Bytes::new(&payload_buf)
29388 } else {
29389 Bytes::new(__input)
29390 };
29391 let mut __struct = Self::default();
29392 __struct.time_boot_ms = buf.get_u32_le()?;
29393 for v in &mut __struct.q {
29394 let val = buf.get_f32_le()?;
29395 *v = val;
29396 }
29397 __struct.body_roll_rate = buf.get_f32_le()?;
29398 __struct.body_pitch_rate = buf.get_f32_le()?;
29399 __struct.body_yaw_rate = buf.get_f32_le()?;
29400 __struct.thrust = buf.get_f32_le()?;
29401 __struct.target_system = buf.get_u8()?;
29402 __struct.target_component = buf.get_u8()?;
29403 let tmp = buf.get_u8()?;
29404 __struct.type_mask =
29405 AttitudeTargetTypemask::from_bits(tmp as <AttitudeTargetTypemask as Flags>::Bits)
29406 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
29407 flag_type: "AttitudeTargetTypemask",
29408 value: tmp as u64,
29409 })?;
29410 for v in &mut __struct.thrust_body {
29411 let val = buf.get_f32_le()?;
29412 *v = val;
29413 }
29414 Ok(__struct)
29415 }
29416 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29417 let mut __tmp = BytesMut::new(bytes);
29418 #[allow(clippy::absurd_extreme_comparisons)]
29419 #[allow(unused_comparisons)]
29420 if __tmp.remaining() < Self::ENCODED_LEN {
29421 panic!(
29422 "buffer is too small (need {} bytes, but got {})",
29423 Self::ENCODED_LEN,
29424 __tmp.remaining(),
29425 )
29426 }
29427 __tmp.put_u32_le(self.time_boot_ms);
29428 for val in &self.q {
29429 __tmp.put_f32_le(*val);
29430 }
29431 __tmp.put_f32_le(self.body_roll_rate);
29432 __tmp.put_f32_le(self.body_pitch_rate);
29433 __tmp.put_f32_le(self.body_yaw_rate);
29434 __tmp.put_f32_le(self.thrust);
29435 __tmp.put_u8(self.target_system);
29436 __tmp.put_u8(self.target_component);
29437 __tmp.put_u8(self.type_mask.bits() as u8);
29438 if matches!(version, MavlinkVersion::V2) {
29439 for val in &self.thrust_body {
29440 __tmp.put_f32_le(*val);
29441 }
29442 let len = __tmp.len();
29443 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29444 } else {
29445 __tmp.len()
29446 }
29447 }
29448}
29449#[deprecated = " See `MAV_CMD_SET_GLOBAL_ORIGIN` (Deprecated since 2025-04)"]
29450#[doc = "Sets the GPS coordinates of the vehicle local origin (0,0,0) position. Vehicle should emit GPS_GLOBAL_ORIGIN irrespective of whether the origin is changed. This enables transform between the local coordinate frame and the global (GPS) coordinate frame, which may be necessary when (for example) indoor and outdoor settings are connected and the MAV should move from in- to outdoor."]
29451#[doc = ""]
29452#[doc = "ID: 48"]
29453#[derive(Debug, Clone, PartialEq)]
29454#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29455#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29456#[cfg_attr(feature = "ts", derive(TS))]
29457#[cfg_attr(feature = "ts", ts(export))]
29458pub struct SET_GPS_GLOBAL_ORIGIN_DATA {
29459 #[doc = "Latitude (WGS84)"]
29460 pub latitude: i32,
29461 #[doc = "Longitude (WGS84)"]
29462 pub longitude: i32,
29463 #[doc = "Altitude (MSL). Positive for up."]
29464 pub altitude: i32,
29465 #[doc = "System ID"]
29466 pub target_system: u8,
29467 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
29468 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29469 pub time_usec: u64,
29470}
29471impl SET_GPS_GLOBAL_ORIGIN_DATA {
29472 pub const ENCODED_LEN: usize = 21usize;
29473 pub const DEFAULT: Self = Self {
29474 latitude: 0_i32,
29475 longitude: 0_i32,
29476 altitude: 0_i32,
29477 target_system: 0_u8,
29478 time_usec: 0_u64,
29479 };
29480 #[cfg(feature = "arbitrary")]
29481 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29482 use arbitrary::{Arbitrary, Unstructured};
29483 let mut buf = [0u8; 1024];
29484 rng.fill_bytes(&mut buf);
29485 let mut unstructured = Unstructured::new(&buf);
29486 Self::arbitrary(&mut unstructured).unwrap_or_default()
29487 }
29488}
29489impl Default for SET_GPS_GLOBAL_ORIGIN_DATA {
29490 fn default() -> Self {
29491 Self::DEFAULT.clone()
29492 }
29493}
29494impl MessageData for SET_GPS_GLOBAL_ORIGIN_DATA {
29495 type Message = MavMessage;
29496 const ID: u32 = 48u32;
29497 const NAME: &'static str = "SET_GPS_GLOBAL_ORIGIN";
29498 const EXTRA_CRC: u8 = 41u8;
29499 const ENCODED_LEN: usize = 21usize;
29500 fn deser(
29501 _version: MavlinkVersion,
29502 __input: &[u8],
29503 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29504 let avail_len = __input.len();
29505 let mut payload_buf = [0; Self::ENCODED_LEN];
29506 let mut buf = if avail_len < Self::ENCODED_LEN {
29507 payload_buf[0..avail_len].copy_from_slice(__input);
29508 Bytes::new(&payload_buf)
29509 } else {
29510 Bytes::new(__input)
29511 };
29512 let mut __struct = Self::default();
29513 __struct.latitude = buf.get_i32_le()?;
29514 __struct.longitude = buf.get_i32_le()?;
29515 __struct.altitude = buf.get_i32_le()?;
29516 __struct.target_system = buf.get_u8()?;
29517 __struct.time_usec = buf.get_u64_le()?;
29518 Ok(__struct)
29519 }
29520 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29521 let mut __tmp = BytesMut::new(bytes);
29522 #[allow(clippy::absurd_extreme_comparisons)]
29523 #[allow(unused_comparisons)]
29524 if __tmp.remaining() < Self::ENCODED_LEN {
29525 panic!(
29526 "buffer is too small (need {} bytes, but got {})",
29527 Self::ENCODED_LEN,
29528 __tmp.remaining(),
29529 )
29530 }
29531 __tmp.put_i32_le(self.latitude);
29532 __tmp.put_i32_le(self.longitude);
29533 __tmp.put_i32_le(self.altitude);
29534 __tmp.put_u8(self.target_system);
29535 if matches!(version, MavlinkVersion::V2) {
29536 __tmp.put_u64_le(self.time_usec);
29537 let len = __tmp.len();
29538 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29539 } else {
29540 __tmp.len()
29541 }
29542 }
29543}
29544#[deprecated = "The command protocol version (MAV_CMD_DO_SET_HOME) allows a GCS to detect when setting the home position has failed. See `MAV_CMD_DO_SET_HOME` (Deprecated since 2022-02)"]
29545#[doc = "Sets the home position. \tThe home position is the default position that the system will return to and land on. The position is set automatically by the system during the takeoff (and may also be set using this message). The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242)."]
29546#[doc = ""]
29547#[doc = "ID: 243"]
29548#[derive(Debug, Clone, PartialEq)]
29549#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29550#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29551#[cfg_attr(feature = "ts", derive(TS))]
29552#[cfg_attr(feature = "ts", ts(export))]
29553pub struct SET_HOME_POSITION_DATA {
29554 #[doc = "Latitude (WGS84)"]
29555 pub latitude: i32,
29556 #[doc = "Longitude (WGS84)"]
29557 pub longitude: i32,
29558 #[doc = "Altitude (MSL). Positive for up."]
29559 pub altitude: i32,
29560 #[doc = "Local X position of this position in the local coordinate frame (NED)"]
29561 pub x: f32,
29562 #[doc = "Local Y position of this position in the local coordinate frame (NED)"]
29563 pub y: f32,
29564 #[doc = "Local Z position of this position in the local coordinate frame (NED: positive \"down\")"]
29565 pub z: f32,
29566 #[doc = "World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground"]
29567 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29568 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
29569 pub q: [f32; 4],
29570 #[doc = "Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
29571 pub approach_x: f32,
29572 #[doc = "Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
29573 pub approach_y: f32,
29574 #[doc = "Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
29575 pub approach_z: f32,
29576 #[doc = "System ID."]
29577 pub target_system: u8,
29578 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
29579 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29580 pub time_usec: u64,
29581}
29582impl SET_HOME_POSITION_DATA {
29583 pub const ENCODED_LEN: usize = 61usize;
29584 pub const DEFAULT: Self = Self {
29585 latitude: 0_i32,
29586 longitude: 0_i32,
29587 altitude: 0_i32,
29588 x: 0.0_f32,
29589 y: 0.0_f32,
29590 z: 0.0_f32,
29591 q: [0.0_f32; 4usize],
29592 approach_x: 0.0_f32,
29593 approach_y: 0.0_f32,
29594 approach_z: 0.0_f32,
29595 target_system: 0_u8,
29596 time_usec: 0_u64,
29597 };
29598 #[cfg(feature = "arbitrary")]
29599 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29600 use arbitrary::{Arbitrary, Unstructured};
29601 let mut buf = [0u8; 1024];
29602 rng.fill_bytes(&mut buf);
29603 let mut unstructured = Unstructured::new(&buf);
29604 Self::arbitrary(&mut unstructured).unwrap_or_default()
29605 }
29606}
29607impl Default for SET_HOME_POSITION_DATA {
29608 fn default() -> Self {
29609 Self::DEFAULT.clone()
29610 }
29611}
29612impl MessageData for SET_HOME_POSITION_DATA {
29613 type Message = MavMessage;
29614 const ID: u32 = 243u32;
29615 const NAME: &'static str = "SET_HOME_POSITION";
29616 const EXTRA_CRC: u8 = 85u8;
29617 const ENCODED_LEN: usize = 61usize;
29618 fn deser(
29619 _version: MavlinkVersion,
29620 __input: &[u8],
29621 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29622 let avail_len = __input.len();
29623 let mut payload_buf = [0; Self::ENCODED_LEN];
29624 let mut buf = if avail_len < Self::ENCODED_LEN {
29625 payload_buf[0..avail_len].copy_from_slice(__input);
29626 Bytes::new(&payload_buf)
29627 } else {
29628 Bytes::new(__input)
29629 };
29630 let mut __struct = Self::default();
29631 __struct.latitude = buf.get_i32_le()?;
29632 __struct.longitude = buf.get_i32_le()?;
29633 __struct.altitude = buf.get_i32_le()?;
29634 __struct.x = buf.get_f32_le()?;
29635 __struct.y = buf.get_f32_le()?;
29636 __struct.z = buf.get_f32_le()?;
29637 for v in &mut __struct.q {
29638 let val = buf.get_f32_le()?;
29639 *v = val;
29640 }
29641 __struct.approach_x = buf.get_f32_le()?;
29642 __struct.approach_y = buf.get_f32_le()?;
29643 __struct.approach_z = buf.get_f32_le()?;
29644 __struct.target_system = buf.get_u8()?;
29645 __struct.time_usec = buf.get_u64_le()?;
29646 Ok(__struct)
29647 }
29648 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29649 let mut __tmp = BytesMut::new(bytes);
29650 #[allow(clippy::absurd_extreme_comparisons)]
29651 #[allow(unused_comparisons)]
29652 if __tmp.remaining() < Self::ENCODED_LEN {
29653 panic!(
29654 "buffer is too small (need {} bytes, but got {})",
29655 Self::ENCODED_LEN,
29656 __tmp.remaining(),
29657 )
29658 }
29659 __tmp.put_i32_le(self.latitude);
29660 __tmp.put_i32_le(self.longitude);
29661 __tmp.put_i32_le(self.altitude);
29662 __tmp.put_f32_le(self.x);
29663 __tmp.put_f32_le(self.y);
29664 __tmp.put_f32_le(self.z);
29665 for val in &self.q {
29666 __tmp.put_f32_le(*val);
29667 }
29668 __tmp.put_f32_le(self.approach_x);
29669 __tmp.put_f32_le(self.approach_y);
29670 __tmp.put_f32_le(self.approach_z);
29671 __tmp.put_u8(self.target_system);
29672 if matches!(version, MavlinkVersion::V2) {
29673 __tmp.put_u64_le(self.time_usec);
29674 let len = __tmp.len();
29675 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29676 } else {
29677 __tmp.len()
29678 }
29679 }
29680}
29681#[deprecated = "Use COMMAND_LONG with MAV_CMD_DO_SET_MODE instead. See `MAV_CMD_DO_SET_MODE` (Deprecated since 2015-12)"]
29682#[doc = "Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component."]
29683#[doc = ""]
29684#[doc = "ID: 11"]
29685#[derive(Debug, Clone, PartialEq)]
29686#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29687#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29688#[cfg_attr(feature = "ts", derive(TS))]
29689#[cfg_attr(feature = "ts", ts(export))]
29690pub struct SET_MODE_DATA {
29691 #[doc = "The new autopilot-specific mode. This field can be ignored by an autopilot."]
29692 pub custom_mode: u32,
29693 #[doc = "The system setting the mode"]
29694 pub target_system: u8,
29695 #[doc = "The new base mode."]
29696 pub base_mode: MavMode,
29697}
29698impl SET_MODE_DATA {
29699 pub const ENCODED_LEN: usize = 6usize;
29700 pub const DEFAULT: Self = Self {
29701 custom_mode: 0_u32,
29702 target_system: 0_u8,
29703 base_mode: MavMode::DEFAULT,
29704 };
29705 #[cfg(feature = "arbitrary")]
29706 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29707 use arbitrary::{Arbitrary, Unstructured};
29708 let mut buf = [0u8; 1024];
29709 rng.fill_bytes(&mut buf);
29710 let mut unstructured = Unstructured::new(&buf);
29711 Self::arbitrary(&mut unstructured).unwrap_or_default()
29712 }
29713}
29714impl Default for SET_MODE_DATA {
29715 fn default() -> Self {
29716 Self::DEFAULT.clone()
29717 }
29718}
29719impl MessageData for SET_MODE_DATA {
29720 type Message = MavMessage;
29721 const ID: u32 = 11u32;
29722 const NAME: &'static str = "SET_MODE";
29723 const EXTRA_CRC: u8 = 89u8;
29724 const ENCODED_LEN: usize = 6usize;
29725 fn deser(
29726 _version: MavlinkVersion,
29727 __input: &[u8],
29728 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29729 let avail_len = __input.len();
29730 let mut payload_buf = [0; Self::ENCODED_LEN];
29731 let mut buf = if avail_len < Self::ENCODED_LEN {
29732 payload_buf[0..avail_len].copy_from_slice(__input);
29733 Bytes::new(&payload_buf)
29734 } else {
29735 Bytes::new(__input)
29736 };
29737 let mut __struct = Self::default();
29738 __struct.custom_mode = buf.get_u32_le()?;
29739 __struct.target_system = buf.get_u8()?;
29740 let tmp = buf.get_u8()?;
29741 __struct.base_mode =
29742 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29743 enum_type: "MavMode",
29744 value: tmp as u64,
29745 })?;
29746 Ok(__struct)
29747 }
29748 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29749 let mut __tmp = BytesMut::new(bytes);
29750 #[allow(clippy::absurd_extreme_comparisons)]
29751 #[allow(unused_comparisons)]
29752 if __tmp.remaining() < Self::ENCODED_LEN {
29753 panic!(
29754 "buffer is too small (need {} bytes, but got {})",
29755 Self::ENCODED_LEN,
29756 __tmp.remaining(),
29757 )
29758 }
29759 __tmp.put_u32_le(self.custom_mode);
29760 __tmp.put_u8(self.target_system);
29761 __tmp.put_u8(self.base_mode as u8);
29762 if matches!(version, MavlinkVersion::V2) {
29763 let len = __tmp.len();
29764 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29765 } else {
29766 __tmp.len()
29767 }
29768 }
29769}
29770#[doc = "Sets a desired vehicle position, velocity, and/or acceleration in a global coordinate system (WGS84). Used by an external controller to command the vehicle (manual controller or other system)."]
29771#[doc = ""]
29772#[doc = "ID: 86"]
29773#[derive(Debug, Clone, PartialEq)]
29774#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29775#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29776#[cfg_attr(feature = "ts", derive(TS))]
29777#[cfg_attr(feature = "ts", ts(export))]
29778pub struct SET_POSITION_TARGET_GLOBAL_INT_DATA {
29779 #[doc = "Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency."]
29780 pub time_boot_ms: u32,
29781 #[doc = "Latitude in WGS84 frame"]
29782 pub lat_int: i32,
29783 #[doc = "Longitude in WGS84 frame"]
29784 pub lon_int: i32,
29785 #[doc = "Altitude (MSL, Relative to home, or AGL - depending on frame)"]
29786 pub alt: f32,
29787 #[doc = "X velocity in NED frame"]
29788 pub vx: f32,
29789 #[doc = "Y velocity in NED frame"]
29790 pub vy: f32,
29791 #[doc = "Z velocity in NED frame"]
29792 pub vz: f32,
29793 #[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
29794 pub afx: f32,
29795 #[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
29796 pub afy: f32,
29797 #[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
29798 pub afz: f32,
29799 #[doc = "yaw setpoint"]
29800 pub yaw: f32,
29801 #[doc = "yaw rate setpoint"]
29802 pub yaw_rate: f32,
29803 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
29804 pub type_mask: PositionTargetTypemask,
29805 #[doc = "System ID"]
29806 pub target_system: u8,
29807 #[doc = "Component ID"]
29808 pub target_component: u8,
29809 #[doc = "Valid options are: MAV_FRAME_GLOBAL = 0, MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 (MAV_FRAME_GLOBAL_INT, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT are allowed synonyms, but have been deprecated)"]
29810 pub coordinate_frame: MavFrame,
29811}
29812impl SET_POSITION_TARGET_GLOBAL_INT_DATA {
29813 pub const ENCODED_LEN: usize = 53usize;
29814 pub const DEFAULT: Self = Self {
29815 time_boot_ms: 0_u32,
29816 lat_int: 0_i32,
29817 lon_int: 0_i32,
29818 alt: 0.0_f32,
29819 vx: 0.0_f32,
29820 vy: 0.0_f32,
29821 vz: 0.0_f32,
29822 afx: 0.0_f32,
29823 afy: 0.0_f32,
29824 afz: 0.0_f32,
29825 yaw: 0.0_f32,
29826 yaw_rate: 0.0_f32,
29827 type_mask: PositionTargetTypemask::DEFAULT,
29828 target_system: 0_u8,
29829 target_component: 0_u8,
29830 coordinate_frame: MavFrame::DEFAULT,
29831 };
29832 #[cfg(feature = "arbitrary")]
29833 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29834 use arbitrary::{Arbitrary, Unstructured};
29835 let mut buf = [0u8; 1024];
29836 rng.fill_bytes(&mut buf);
29837 let mut unstructured = Unstructured::new(&buf);
29838 Self::arbitrary(&mut unstructured).unwrap_or_default()
29839 }
29840}
29841impl Default for SET_POSITION_TARGET_GLOBAL_INT_DATA {
29842 fn default() -> Self {
29843 Self::DEFAULT.clone()
29844 }
29845}
29846impl MessageData for SET_POSITION_TARGET_GLOBAL_INT_DATA {
29847 type Message = MavMessage;
29848 const ID: u32 = 86u32;
29849 const NAME: &'static str = "SET_POSITION_TARGET_GLOBAL_INT";
29850 const EXTRA_CRC: u8 = 5u8;
29851 const ENCODED_LEN: usize = 53usize;
29852 fn deser(
29853 _version: MavlinkVersion,
29854 __input: &[u8],
29855 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29856 let avail_len = __input.len();
29857 let mut payload_buf = [0; Self::ENCODED_LEN];
29858 let mut buf = if avail_len < Self::ENCODED_LEN {
29859 payload_buf[0..avail_len].copy_from_slice(__input);
29860 Bytes::new(&payload_buf)
29861 } else {
29862 Bytes::new(__input)
29863 };
29864 let mut __struct = Self::default();
29865 __struct.time_boot_ms = buf.get_u32_le()?;
29866 __struct.lat_int = buf.get_i32_le()?;
29867 __struct.lon_int = buf.get_i32_le()?;
29868 __struct.alt = buf.get_f32_le()?;
29869 __struct.vx = buf.get_f32_le()?;
29870 __struct.vy = buf.get_f32_le()?;
29871 __struct.vz = buf.get_f32_le()?;
29872 __struct.afx = buf.get_f32_le()?;
29873 __struct.afy = buf.get_f32_le()?;
29874 __struct.afz = buf.get_f32_le()?;
29875 __struct.yaw = buf.get_f32_le()?;
29876 __struct.yaw_rate = buf.get_f32_le()?;
29877 let tmp = buf.get_u16_le()?;
29878 __struct.type_mask =
29879 PositionTargetTypemask::from_bits(tmp as <PositionTargetTypemask as Flags>::Bits)
29880 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
29881 flag_type: "PositionTargetTypemask",
29882 value: tmp as u64,
29883 })?;
29884 __struct.target_system = buf.get_u8()?;
29885 __struct.target_component = buf.get_u8()?;
29886 let tmp = buf.get_u8()?;
29887 __struct.coordinate_frame =
29888 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29889 enum_type: "MavFrame",
29890 value: tmp as u64,
29891 })?;
29892 Ok(__struct)
29893 }
29894 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29895 let mut __tmp = BytesMut::new(bytes);
29896 #[allow(clippy::absurd_extreme_comparisons)]
29897 #[allow(unused_comparisons)]
29898 if __tmp.remaining() < Self::ENCODED_LEN {
29899 panic!(
29900 "buffer is too small (need {} bytes, but got {})",
29901 Self::ENCODED_LEN,
29902 __tmp.remaining(),
29903 )
29904 }
29905 __tmp.put_u32_le(self.time_boot_ms);
29906 __tmp.put_i32_le(self.lat_int);
29907 __tmp.put_i32_le(self.lon_int);
29908 __tmp.put_f32_le(self.alt);
29909 __tmp.put_f32_le(self.vx);
29910 __tmp.put_f32_le(self.vy);
29911 __tmp.put_f32_le(self.vz);
29912 __tmp.put_f32_le(self.afx);
29913 __tmp.put_f32_le(self.afy);
29914 __tmp.put_f32_le(self.afz);
29915 __tmp.put_f32_le(self.yaw);
29916 __tmp.put_f32_le(self.yaw_rate);
29917 __tmp.put_u16_le(self.type_mask.bits() as u16);
29918 __tmp.put_u8(self.target_system);
29919 __tmp.put_u8(self.target_component);
29920 __tmp.put_u8(self.coordinate_frame as u8);
29921 if matches!(version, MavlinkVersion::V2) {
29922 let len = __tmp.len();
29923 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29924 } else {
29925 __tmp.len()
29926 }
29927 }
29928}
29929#[doc = "Sets a desired vehicle position in a local north-east-down coordinate frame. Used by an external controller to command the vehicle (manual controller or other system)."]
29930#[doc = ""]
29931#[doc = "ID: 84"]
29932#[derive(Debug, Clone, PartialEq)]
29933#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29934#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29935#[cfg_attr(feature = "ts", derive(TS))]
29936#[cfg_attr(feature = "ts", ts(export))]
29937pub struct SET_POSITION_TARGET_LOCAL_NED_DATA {
29938 #[doc = "Timestamp (time since system boot)."]
29939 pub time_boot_ms: u32,
29940 #[doc = "X Position in NED frame"]
29941 pub x: f32,
29942 #[doc = "Y Position in NED frame"]
29943 pub y: f32,
29944 #[doc = "Z Position in NED frame (note, altitude is negative in NED)"]
29945 pub z: f32,
29946 #[doc = "X velocity in NED frame"]
29947 pub vx: f32,
29948 #[doc = "Y velocity in NED frame"]
29949 pub vy: f32,
29950 #[doc = "Z velocity in NED frame"]
29951 pub vz: f32,
29952 #[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
29953 pub afx: f32,
29954 #[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
29955 pub afy: f32,
29956 #[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
29957 pub afz: f32,
29958 #[doc = "yaw setpoint"]
29959 pub yaw: f32,
29960 #[doc = "yaw rate setpoint"]
29961 pub yaw_rate: f32,
29962 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
29963 pub type_mask: PositionTargetTypemask,
29964 #[doc = "System ID"]
29965 pub target_system: u8,
29966 #[doc = "Component ID"]
29967 pub target_component: u8,
29968 #[doc = "Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9"]
29969 pub coordinate_frame: MavFrame,
29970}
29971impl SET_POSITION_TARGET_LOCAL_NED_DATA {
29972 pub const ENCODED_LEN: usize = 53usize;
29973 pub const DEFAULT: Self = Self {
29974 time_boot_ms: 0_u32,
29975 x: 0.0_f32,
29976 y: 0.0_f32,
29977 z: 0.0_f32,
29978 vx: 0.0_f32,
29979 vy: 0.0_f32,
29980 vz: 0.0_f32,
29981 afx: 0.0_f32,
29982 afy: 0.0_f32,
29983 afz: 0.0_f32,
29984 yaw: 0.0_f32,
29985 yaw_rate: 0.0_f32,
29986 type_mask: PositionTargetTypemask::DEFAULT,
29987 target_system: 0_u8,
29988 target_component: 0_u8,
29989 coordinate_frame: MavFrame::DEFAULT,
29990 };
29991 #[cfg(feature = "arbitrary")]
29992 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29993 use arbitrary::{Arbitrary, Unstructured};
29994 let mut buf = [0u8; 1024];
29995 rng.fill_bytes(&mut buf);
29996 let mut unstructured = Unstructured::new(&buf);
29997 Self::arbitrary(&mut unstructured).unwrap_or_default()
29998 }
29999}
30000impl Default for SET_POSITION_TARGET_LOCAL_NED_DATA {
30001 fn default() -> Self {
30002 Self::DEFAULT.clone()
30003 }
30004}
30005impl MessageData for SET_POSITION_TARGET_LOCAL_NED_DATA {
30006 type Message = MavMessage;
30007 const ID: u32 = 84u32;
30008 const NAME: &'static str = "SET_POSITION_TARGET_LOCAL_NED";
30009 const EXTRA_CRC: u8 = 143u8;
30010 const ENCODED_LEN: usize = 53usize;
30011 fn deser(
30012 _version: MavlinkVersion,
30013 __input: &[u8],
30014 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30015 let avail_len = __input.len();
30016 let mut payload_buf = [0; Self::ENCODED_LEN];
30017 let mut buf = if avail_len < Self::ENCODED_LEN {
30018 payload_buf[0..avail_len].copy_from_slice(__input);
30019 Bytes::new(&payload_buf)
30020 } else {
30021 Bytes::new(__input)
30022 };
30023 let mut __struct = Self::default();
30024 __struct.time_boot_ms = buf.get_u32_le()?;
30025 __struct.x = buf.get_f32_le()?;
30026 __struct.y = buf.get_f32_le()?;
30027 __struct.z = buf.get_f32_le()?;
30028 __struct.vx = buf.get_f32_le()?;
30029 __struct.vy = buf.get_f32_le()?;
30030 __struct.vz = buf.get_f32_le()?;
30031 __struct.afx = buf.get_f32_le()?;
30032 __struct.afy = buf.get_f32_le()?;
30033 __struct.afz = buf.get_f32_le()?;
30034 __struct.yaw = buf.get_f32_le()?;
30035 __struct.yaw_rate = buf.get_f32_le()?;
30036 let tmp = buf.get_u16_le()?;
30037 __struct.type_mask =
30038 PositionTargetTypemask::from_bits(tmp as <PositionTargetTypemask as Flags>::Bits)
30039 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
30040 flag_type: "PositionTargetTypemask",
30041 value: tmp as u64,
30042 })?;
30043 __struct.target_system = buf.get_u8()?;
30044 __struct.target_component = buf.get_u8()?;
30045 let tmp = buf.get_u8()?;
30046 __struct.coordinate_frame =
30047 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30048 enum_type: "MavFrame",
30049 value: tmp as u64,
30050 })?;
30051 Ok(__struct)
30052 }
30053 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30054 let mut __tmp = BytesMut::new(bytes);
30055 #[allow(clippy::absurd_extreme_comparisons)]
30056 #[allow(unused_comparisons)]
30057 if __tmp.remaining() < Self::ENCODED_LEN {
30058 panic!(
30059 "buffer is too small (need {} bytes, but got {})",
30060 Self::ENCODED_LEN,
30061 __tmp.remaining(),
30062 )
30063 }
30064 __tmp.put_u32_le(self.time_boot_ms);
30065 __tmp.put_f32_le(self.x);
30066 __tmp.put_f32_le(self.y);
30067 __tmp.put_f32_le(self.z);
30068 __tmp.put_f32_le(self.vx);
30069 __tmp.put_f32_le(self.vy);
30070 __tmp.put_f32_le(self.vz);
30071 __tmp.put_f32_le(self.afx);
30072 __tmp.put_f32_le(self.afy);
30073 __tmp.put_f32_le(self.afz);
30074 __tmp.put_f32_le(self.yaw);
30075 __tmp.put_f32_le(self.yaw_rate);
30076 __tmp.put_u16_le(self.type_mask.bits() as u16);
30077 __tmp.put_u8(self.target_system);
30078 __tmp.put_u8(self.target_component);
30079 __tmp.put_u8(self.coordinate_frame as u8);
30080 if matches!(version, MavlinkVersion::V2) {
30081 let len = __tmp.len();
30082 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30083 } else {
30084 __tmp.len()
30085 }
30086 }
30087}
30088#[doc = "Status of simulation environment, if used."]
30089#[doc = ""]
30090#[doc = "ID: 108"]
30091#[derive(Debug, Clone, PartialEq)]
30092#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30093#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30094#[cfg_attr(feature = "ts", derive(TS))]
30095#[cfg_attr(feature = "ts", ts(export))]
30096pub struct SIM_STATE_DATA {
30097 #[doc = "True attitude quaternion component 1, w (1 in null-rotation)"]
30098 pub q1: f32,
30099 #[doc = "True attitude quaternion component 2, x (0 in null-rotation)"]
30100 pub q2: f32,
30101 #[doc = "True attitude quaternion component 3, y (0 in null-rotation)"]
30102 pub q3: f32,
30103 #[doc = "True attitude quaternion component 4, z (0 in null-rotation)"]
30104 pub q4: f32,
30105 #[doc = "Attitude roll expressed as Euler angles, not recommended except for human-readable outputs"]
30106 pub roll: f32,
30107 #[doc = "Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs"]
30108 pub pitch: f32,
30109 #[doc = "Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs"]
30110 pub yaw: f32,
30111 #[doc = "X acceleration"]
30112 pub xacc: f32,
30113 #[doc = "Y acceleration"]
30114 pub yacc: f32,
30115 #[doc = "Z acceleration"]
30116 pub zacc: f32,
30117 #[doc = "Angular speed around X axis"]
30118 pub xgyro: f32,
30119 #[doc = "Angular speed around Y axis"]
30120 pub ygyro: f32,
30121 #[doc = "Angular speed around Z axis"]
30122 pub zgyro: f32,
30123 #[doc = "Latitude (lower precision). Both this and the lat_int field should be set."]
30124 pub lat: f32,
30125 #[doc = "Longitude (lower precision). Both this and the lon_int field should be set."]
30126 pub lon: f32,
30127 #[doc = "Altitude"]
30128 pub alt: f32,
30129 #[doc = "Horizontal position standard deviation"]
30130 pub std_dev_horz: f32,
30131 #[doc = "Vertical position standard deviation"]
30132 pub std_dev_vert: f32,
30133 #[doc = "True velocity in north direction in earth-fixed NED frame"]
30134 pub vn: f32,
30135 #[doc = "True velocity in east direction in earth-fixed NED frame"]
30136 pub ve: f32,
30137 #[doc = "True velocity in down direction in earth-fixed NED frame"]
30138 pub vd: f32,
30139 #[doc = "Latitude (higher precision). If 0, recipients should use the lat field value (otherwise this field is preferred)."]
30140 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30141 pub lat_int: i32,
30142 #[doc = "Longitude (higher precision). If 0, recipients should use the lon field value (otherwise this field is preferred)."]
30143 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30144 pub lon_int: i32,
30145}
30146impl SIM_STATE_DATA {
30147 pub const ENCODED_LEN: usize = 92usize;
30148 pub const DEFAULT: Self = Self {
30149 q1: 0.0_f32,
30150 q2: 0.0_f32,
30151 q3: 0.0_f32,
30152 q4: 0.0_f32,
30153 roll: 0.0_f32,
30154 pitch: 0.0_f32,
30155 yaw: 0.0_f32,
30156 xacc: 0.0_f32,
30157 yacc: 0.0_f32,
30158 zacc: 0.0_f32,
30159 xgyro: 0.0_f32,
30160 ygyro: 0.0_f32,
30161 zgyro: 0.0_f32,
30162 lat: 0.0_f32,
30163 lon: 0.0_f32,
30164 alt: 0.0_f32,
30165 std_dev_horz: 0.0_f32,
30166 std_dev_vert: 0.0_f32,
30167 vn: 0.0_f32,
30168 ve: 0.0_f32,
30169 vd: 0.0_f32,
30170 lat_int: 0_i32,
30171 lon_int: 0_i32,
30172 };
30173 #[cfg(feature = "arbitrary")]
30174 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30175 use arbitrary::{Arbitrary, Unstructured};
30176 let mut buf = [0u8; 1024];
30177 rng.fill_bytes(&mut buf);
30178 let mut unstructured = Unstructured::new(&buf);
30179 Self::arbitrary(&mut unstructured).unwrap_or_default()
30180 }
30181}
30182impl Default for SIM_STATE_DATA {
30183 fn default() -> Self {
30184 Self::DEFAULT.clone()
30185 }
30186}
30187impl MessageData for SIM_STATE_DATA {
30188 type Message = MavMessage;
30189 const ID: u32 = 108u32;
30190 const NAME: &'static str = "SIM_STATE";
30191 const EXTRA_CRC: u8 = 32u8;
30192 const ENCODED_LEN: usize = 92usize;
30193 fn deser(
30194 _version: MavlinkVersion,
30195 __input: &[u8],
30196 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30197 let avail_len = __input.len();
30198 let mut payload_buf = [0; Self::ENCODED_LEN];
30199 let mut buf = if avail_len < Self::ENCODED_LEN {
30200 payload_buf[0..avail_len].copy_from_slice(__input);
30201 Bytes::new(&payload_buf)
30202 } else {
30203 Bytes::new(__input)
30204 };
30205 let mut __struct = Self::default();
30206 __struct.q1 = buf.get_f32_le()?;
30207 __struct.q2 = buf.get_f32_le()?;
30208 __struct.q3 = buf.get_f32_le()?;
30209 __struct.q4 = buf.get_f32_le()?;
30210 __struct.roll = buf.get_f32_le()?;
30211 __struct.pitch = buf.get_f32_le()?;
30212 __struct.yaw = buf.get_f32_le()?;
30213 __struct.xacc = buf.get_f32_le()?;
30214 __struct.yacc = buf.get_f32_le()?;
30215 __struct.zacc = buf.get_f32_le()?;
30216 __struct.xgyro = buf.get_f32_le()?;
30217 __struct.ygyro = buf.get_f32_le()?;
30218 __struct.zgyro = buf.get_f32_le()?;
30219 __struct.lat = buf.get_f32_le()?;
30220 __struct.lon = buf.get_f32_le()?;
30221 __struct.alt = buf.get_f32_le()?;
30222 __struct.std_dev_horz = buf.get_f32_le()?;
30223 __struct.std_dev_vert = buf.get_f32_le()?;
30224 __struct.vn = buf.get_f32_le()?;
30225 __struct.ve = buf.get_f32_le()?;
30226 __struct.vd = buf.get_f32_le()?;
30227 __struct.lat_int = buf.get_i32_le()?;
30228 __struct.lon_int = buf.get_i32_le()?;
30229 Ok(__struct)
30230 }
30231 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30232 let mut __tmp = BytesMut::new(bytes);
30233 #[allow(clippy::absurd_extreme_comparisons)]
30234 #[allow(unused_comparisons)]
30235 if __tmp.remaining() < Self::ENCODED_LEN {
30236 panic!(
30237 "buffer is too small (need {} bytes, but got {})",
30238 Self::ENCODED_LEN,
30239 __tmp.remaining(),
30240 )
30241 }
30242 __tmp.put_f32_le(self.q1);
30243 __tmp.put_f32_le(self.q2);
30244 __tmp.put_f32_le(self.q3);
30245 __tmp.put_f32_le(self.q4);
30246 __tmp.put_f32_le(self.roll);
30247 __tmp.put_f32_le(self.pitch);
30248 __tmp.put_f32_le(self.yaw);
30249 __tmp.put_f32_le(self.xacc);
30250 __tmp.put_f32_le(self.yacc);
30251 __tmp.put_f32_le(self.zacc);
30252 __tmp.put_f32_le(self.xgyro);
30253 __tmp.put_f32_le(self.ygyro);
30254 __tmp.put_f32_le(self.zgyro);
30255 __tmp.put_f32_le(self.lat);
30256 __tmp.put_f32_le(self.lon);
30257 __tmp.put_f32_le(self.alt);
30258 __tmp.put_f32_le(self.std_dev_horz);
30259 __tmp.put_f32_le(self.std_dev_vert);
30260 __tmp.put_f32_le(self.vn);
30261 __tmp.put_f32_le(self.ve);
30262 __tmp.put_f32_le(self.vd);
30263 if matches!(version, MavlinkVersion::V2) {
30264 __tmp.put_i32_le(self.lat_int);
30265 __tmp.put_i32_le(self.lon_int);
30266 let len = __tmp.len();
30267 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30268 } else {
30269 __tmp.len()
30270 }
30271 }
30272}
30273#[deprecated = "The BATTERY_INFO message is better aligned with UAVCAN messages, and in any case is useful even if a battery is not \"smart\". See `BATTERY_INFO` (Deprecated since 2024-02)"]
30274#[doc = "Smart Battery information (static/infrequent update). Use for updates from: smart battery to flight stack, flight stack to GCS. Use BATTERY_STATUS for the frequent battery updates."]
30275#[doc = ""]
30276#[doc = "ID: 370"]
30277#[derive(Debug, Clone, PartialEq)]
30278#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30279#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30280#[cfg_attr(feature = "ts", derive(TS))]
30281#[cfg_attr(feature = "ts", ts(export))]
30282pub struct SMART_BATTERY_INFO_DATA {
30283 #[doc = "Capacity when full according to manufacturer, -1: field not provided."]
30284 pub capacity_full_specification: i32,
30285 #[doc = "Capacity when full (accounting for battery degradation), -1: field not provided."]
30286 pub capacity_full: i32,
30287 #[doc = "Charge/discharge cycle count. UINT16_MAX: field not provided."]
30288 pub cycle_count: u16,
30289 #[doc = "Battery weight. 0: field not provided."]
30290 pub weight: u16,
30291 #[doc = "Minimum per-cell voltage when discharging. If not supplied set to UINT16_MAX value."]
30292 pub discharge_minimum_voltage: u16,
30293 #[doc = "Minimum per-cell voltage when charging. If not supplied set to UINT16_MAX value."]
30294 pub charging_minimum_voltage: u16,
30295 #[doc = "Minimum per-cell voltage when resting. If not supplied set to UINT16_MAX value."]
30296 pub resting_minimum_voltage: u16,
30297 #[doc = "Battery ID"]
30298 pub id: u8,
30299 #[doc = "Function of the battery"]
30300 pub battery_function: MavBatteryFunction,
30301 #[doc = "Type (chemistry) of the battery"]
30302 pub mavtype: MavBatteryType,
30303 #[doc = "Serial number in ASCII characters, 0 terminated. All 0: field not provided."]
30304 #[cfg_attr(feature = "ts", ts(type = "string"))]
30305 pub serial_number: CharArray<16>,
30306 #[doc = "Static device name in ASCII characters, 0 terminated. All 0: field not provided. Encode as manufacturer name then product name separated using an underscore."]
30307 #[cfg_attr(feature = "ts", ts(type = "string"))]
30308 pub device_name: CharArray<50>,
30309 #[doc = "Maximum per-cell voltage when charged. 0: field not provided."]
30310 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30311 pub charging_maximum_voltage: u16,
30312 #[doc = "Number of battery cells in series. 0: field not provided."]
30313 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30314 pub cells_in_series: u8,
30315 #[doc = "Maximum pack discharge current. 0: field not provided."]
30316 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30317 pub discharge_maximum_current: u32,
30318 #[doc = "Maximum pack discharge burst current. 0: field not provided."]
30319 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30320 pub discharge_maximum_burst_current: u32,
30321 #[doc = "Manufacture date (DD/MM/YYYY) in ASCII characters, 0 terminated. All 0: field not provided."]
30322 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30323 #[cfg_attr(feature = "ts", ts(type = "string"))]
30324 pub manufacture_date: CharArray<11>,
30325}
30326impl SMART_BATTERY_INFO_DATA {
30327 pub const ENCODED_LEN: usize = 109usize;
30328 pub const DEFAULT: Self = Self {
30329 capacity_full_specification: 0_i32,
30330 capacity_full: 0_i32,
30331 cycle_count: 0_u16,
30332 weight: 0_u16,
30333 discharge_minimum_voltage: 0_u16,
30334 charging_minimum_voltage: 0_u16,
30335 resting_minimum_voltage: 0_u16,
30336 id: 0_u8,
30337 battery_function: MavBatteryFunction::DEFAULT,
30338 mavtype: MavBatteryType::DEFAULT,
30339 serial_number: CharArray::new([0_u8; 16usize]),
30340 device_name: CharArray::new([0_u8; 50usize]),
30341 charging_maximum_voltage: 0_u16,
30342 cells_in_series: 0_u8,
30343 discharge_maximum_current: 0_u32,
30344 discharge_maximum_burst_current: 0_u32,
30345 manufacture_date: CharArray::new([0_u8; 11usize]),
30346 };
30347 #[cfg(feature = "arbitrary")]
30348 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30349 use arbitrary::{Arbitrary, Unstructured};
30350 let mut buf = [0u8; 1024];
30351 rng.fill_bytes(&mut buf);
30352 let mut unstructured = Unstructured::new(&buf);
30353 Self::arbitrary(&mut unstructured).unwrap_or_default()
30354 }
30355}
30356impl Default for SMART_BATTERY_INFO_DATA {
30357 fn default() -> Self {
30358 Self::DEFAULT.clone()
30359 }
30360}
30361impl MessageData for SMART_BATTERY_INFO_DATA {
30362 type Message = MavMessage;
30363 const ID: u32 = 370u32;
30364 const NAME: &'static str = "SMART_BATTERY_INFO";
30365 const EXTRA_CRC: u8 = 75u8;
30366 const ENCODED_LEN: usize = 109usize;
30367 fn deser(
30368 _version: MavlinkVersion,
30369 __input: &[u8],
30370 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30371 let avail_len = __input.len();
30372 let mut payload_buf = [0; Self::ENCODED_LEN];
30373 let mut buf = if avail_len < Self::ENCODED_LEN {
30374 payload_buf[0..avail_len].copy_from_slice(__input);
30375 Bytes::new(&payload_buf)
30376 } else {
30377 Bytes::new(__input)
30378 };
30379 let mut __struct = Self::default();
30380 __struct.capacity_full_specification = buf.get_i32_le()?;
30381 __struct.capacity_full = buf.get_i32_le()?;
30382 __struct.cycle_count = buf.get_u16_le()?;
30383 __struct.weight = buf.get_u16_le()?;
30384 __struct.discharge_minimum_voltage = buf.get_u16_le()?;
30385 __struct.charging_minimum_voltage = buf.get_u16_le()?;
30386 __struct.resting_minimum_voltage = buf.get_u16_le()?;
30387 __struct.id = buf.get_u8()?;
30388 let tmp = buf.get_u8()?;
30389 __struct.battery_function =
30390 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30391 enum_type: "MavBatteryFunction",
30392 value: tmp as u64,
30393 })?;
30394 let tmp = buf.get_u8()?;
30395 __struct.mavtype =
30396 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30397 enum_type: "MavBatteryType",
30398 value: tmp as u64,
30399 })?;
30400 let mut tmp = [0_u8; 16usize];
30401 for v in &mut tmp {
30402 *v = buf.get_u8()?;
30403 }
30404 __struct.serial_number = CharArray::new(tmp);
30405 let mut tmp = [0_u8; 50usize];
30406 for v in &mut tmp {
30407 *v = buf.get_u8()?;
30408 }
30409 __struct.device_name = CharArray::new(tmp);
30410 __struct.charging_maximum_voltage = buf.get_u16_le()?;
30411 __struct.cells_in_series = buf.get_u8()?;
30412 __struct.discharge_maximum_current = buf.get_u32_le()?;
30413 __struct.discharge_maximum_burst_current = buf.get_u32_le()?;
30414 let mut tmp = [0_u8; 11usize];
30415 for v in &mut tmp {
30416 *v = buf.get_u8()?;
30417 }
30418 __struct.manufacture_date = CharArray::new(tmp);
30419 Ok(__struct)
30420 }
30421 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30422 let mut __tmp = BytesMut::new(bytes);
30423 #[allow(clippy::absurd_extreme_comparisons)]
30424 #[allow(unused_comparisons)]
30425 if __tmp.remaining() < Self::ENCODED_LEN {
30426 panic!(
30427 "buffer is too small (need {} bytes, but got {})",
30428 Self::ENCODED_LEN,
30429 __tmp.remaining(),
30430 )
30431 }
30432 __tmp.put_i32_le(self.capacity_full_specification);
30433 __tmp.put_i32_le(self.capacity_full);
30434 __tmp.put_u16_le(self.cycle_count);
30435 __tmp.put_u16_le(self.weight);
30436 __tmp.put_u16_le(self.discharge_minimum_voltage);
30437 __tmp.put_u16_le(self.charging_minimum_voltage);
30438 __tmp.put_u16_le(self.resting_minimum_voltage);
30439 __tmp.put_u8(self.id);
30440 __tmp.put_u8(self.battery_function as u8);
30441 __tmp.put_u8(self.mavtype as u8);
30442 for val in &self.serial_number {
30443 __tmp.put_u8(*val);
30444 }
30445 for val in &self.device_name {
30446 __tmp.put_u8(*val);
30447 }
30448 if matches!(version, MavlinkVersion::V2) {
30449 __tmp.put_u16_le(self.charging_maximum_voltage);
30450 __tmp.put_u8(self.cells_in_series);
30451 __tmp.put_u32_le(self.discharge_maximum_current);
30452 __tmp.put_u32_le(self.discharge_maximum_burst_current);
30453 for val in &self.manufacture_date {
30454 __tmp.put_u8(*val);
30455 }
30456 let len = __tmp.len();
30457 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30458 } else {
30459 __tmp.len()
30460 }
30461 }
30462}
30463#[doc = "Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz)."]
30464#[doc = ""]
30465#[doc = "ID: 253"]
30466#[derive(Debug, Clone, PartialEq)]
30467#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30468#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30469#[cfg_attr(feature = "ts", derive(TS))]
30470#[cfg_attr(feature = "ts", ts(export))]
30471pub struct STATUSTEXT_DATA {
30472 #[doc = "Severity of status. Relies on the definitions within RFC-5424."]
30473 pub severity: MavSeverity,
30474 #[doc = "Status text message, without null termination character"]
30475 #[cfg_attr(feature = "ts", ts(type = "string"))]
30476 pub text: CharArray<50>,
30477 #[doc = "Unique (opaque) identifier for this statustext message. May be used to reassemble a logical long-statustext message from a sequence of chunks. A value of zero indicates this is the only chunk in the sequence and the message can be emitted immediately."]
30478 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30479 pub id: u16,
30480 #[doc = "This chunk's sequence number; indexing is from zero. Any null character in the text field is taken to mean this was the last chunk."]
30481 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30482 pub chunk_seq: u8,
30483}
30484impl STATUSTEXT_DATA {
30485 pub const ENCODED_LEN: usize = 54usize;
30486 pub const DEFAULT: Self = Self {
30487 severity: MavSeverity::DEFAULT,
30488 text: CharArray::new([0_u8; 50usize]),
30489 id: 0_u16,
30490 chunk_seq: 0_u8,
30491 };
30492 #[cfg(feature = "arbitrary")]
30493 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30494 use arbitrary::{Arbitrary, Unstructured};
30495 let mut buf = [0u8; 1024];
30496 rng.fill_bytes(&mut buf);
30497 let mut unstructured = Unstructured::new(&buf);
30498 Self::arbitrary(&mut unstructured).unwrap_or_default()
30499 }
30500}
30501impl Default for STATUSTEXT_DATA {
30502 fn default() -> Self {
30503 Self::DEFAULT.clone()
30504 }
30505}
30506impl MessageData for STATUSTEXT_DATA {
30507 type Message = MavMessage;
30508 const ID: u32 = 253u32;
30509 const NAME: &'static str = "STATUSTEXT";
30510 const EXTRA_CRC: u8 = 83u8;
30511 const ENCODED_LEN: usize = 54usize;
30512 fn deser(
30513 _version: MavlinkVersion,
30514 __input: &[u8],
30515 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30516 let avail_len = __input.len();
30517 let mut payload_buf = [0; Self::ENCODED_LEN];
30518 let mut buf = if avail_len < Self::ENCODED_LEN {
30519 payload_buf[0..avail_len].copy_from_slice(__input);
30520 Bytes::new(&payload_buf)
30521 } else {
30522 Bytes::new(__input)
30523 };
30524 let mut __struct = Self::default();
30525 let tmp = buf.get_u8()?;
30526 __struct.severity =
30527 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30528 enum_type: "MavSeverity",
30529 value: tmp as u64,
30530 })?;
30531 let mut tmp = [0_u8; 50usize];
30532 for v in &mut tmp {
30533 *v = buf.get_u8()?;
30534 }
30535 __struct.text = CharArray::new(tmp);
30536 __struct.id = buf.get_u16_le()?;
30537 __struct.chunk_seq = buf.get_u8()?;
30538 Ok(__struct)
30539 }
30540 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30541 let mut __tmp = BytesMut::new(bytes);
30542 #[allow(clippy::absurd_extreme_comparisons)]
30543 #[allow(unused_comparisons)]
30544 if __tmp.remaining() < Self::ENCODED_LEN {
30545 panic!(
30546 "buffer is too small (need {} bytes, but got {})",
30547 Self::ENCODED_LEN,
30548 __tmp.remaining(),
30549 )
30550 }
30551 __tmp.put_u8(self.severity as u8);
30552 for val in &self.text {
30553 __tmp.put_u8(*val);
30554 }
30555 if matches!(version, MavlinkVersion::V2) {
30556 __tmp.put_u16_le(self.id);
30557 __tmp.put_u8(self.chunk_seq);
30558 let len = __tmp.len();
30559 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30560 } else {
30561 __tmp.len()
30562 }
30563 }
30564}
30565#[doc = "Information about a storage medium. This message is sent in response to a request with MAV_CMD_REQUEST_MESSAGE and whenever the status of the storage changes (STORAGE_STATUS). Use MAV_CMD_REQUEST_MESSAGE.param2 to indicate the index/id of requested storage: 0 for all, 1 for first, 2 for second, etc."]
30566#[doc = ""]
30567#[doc = "ID: 261"]
30568#[derive(Debug, Clone, PartialEq)]
30569#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30570#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30571#[cfg_attr(feature = "ts", derive(TS))]
30572#[cfg_attr(feature = "ts", ts(export))]
30573pub struct STORAGE_INFORMATION_DATA {
30574 #[doc = "Timestamp (time since system boot)."]
30575 pub time_boot_ms: u32,
30576 #[doc = "Total capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored."]
30577 pub total_capacity: f32,
30578 #[doc = "Used capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored."]
30579 pub used_capacity: f32,
30580 #[doc = "Available storage capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored."]
30581 pub available_capacity: f32,
30582 #[doc = "Read speed."]
30583 pub read_speed: f32,
30584 #[doc = "Write speed."]
30585 pub write_speed: f32,
30586 #[doc = "Storage ID (1 for first, 2 for second, etc.)"]
30587 pub storage_id: u8,
30588 #[doc = "Number of storage devices"]
30589 pub storage_count: u8,
30590 #[doc = "Status of storage"]
30591 pub status: StorageStatus,
30592 #[doc = "Type of storage"]
30593 #[cfg_attr(feature = "serde", serde(default))]
30594 pub mavtype: StorageType,
30595 #[doc = "Textual storage name to be used in UI (microSD 1, Internal Memory, etc.) This is a NULL terminated string. If it is exactly 32 characters long, add a terminating NULL. If this string is empty, the generic type is shown to the user."]
30596 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30597 #[cfg_attr(feature = "ts", ts(type = "string"))]
30598 pub name: CharArray<32>,
30599 #[doc = "Flags indicating whether this instance is preferred storage for photos, videos, etc. Note: Implementations should initially set the flags on the system-default storage id used for saving media (if possible/supported). This setting can then be overridden using MAV_CMD_SET_STORAGE_USAGE. If the media usage flags are not set, a GCS may assume storage ID 1 is the default storage for all media types."]
30600 #[cfg_attr(feature = "serde", serde(default))]
30601 pub storage_usage: StorageUsageFlag,
30602}
30603impl STORAGE_INFORMATION_DATA {
30604 pub const ENCODED_LEN: usize = 61usize;
30605 pub const DEFAULT: Self = Self {
30606 time_boot_ms: 0_u32,
30607 total_capacity: 0.0_f32,
30608 used_capacity: 0.0_f32,
30609 available_capacity: 0.0_f32,
30610 read_speed: 0.0_f32,
30611 write_speed: 0.0_f32,
30612 storage_id: 0_u8,
30613 storage_count: 0_u8,
30614 status: StorageStatus::DEFAULT,
30615 mavtype: StorageType::DEFAULT,
30616 name: CharArray::new([0_u8; 32usize]),
30617 storage_usage: StorageUsageFlag::DEFAULT,
30618 };
30619 #[cfg(feature = "arbitrary")]
30620 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30621 use arbitrary::{Arbitrary, Unstructured};
30622 let mut buf = [0u8; 1024];
30623 rng.fill_bytes(&mut buf);
30624 let mut unstructured = Unstructured::new(&buf);
30625 Self::arbitrary(&mut unstructured).unwrap_or_default()
30626 }
30627}
30628impl Default for STORAGE_INFORMATION_DATA {
30629 fn default() -> Self {
30630 Self::DEFAULT.clone()
30631 }
30632}
30633impl MessageData for STORAGE_INFORMATION_DATA {
30634 type Message = MavMessage;
30635 const ID: u32 = 261u32;
30636 const NAME: &'static str = "STORAGE_INFORMATION";
30637 const EXTRA_CRC: u8 = 179u8;
30638 const ENCODED_LEN: usize = 61usize;
30639 fn deser(
30640 _version: MavlinkVersion,
30641 __input: &[u8],
30642 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30643 let avail_len = __input.len();
30644 let mut payload_buf = [0; Self::ENCODED_LEN];
30645 let mut buf = if avail_len < Self::ENCODED_LEN {
30646 payload_buf[0..avail_len].copy_from_slice(__input);
30647 Bytes::new(&payload_buf)
30648 } else {
30649 Bytes::new(__input)
30650 };
30651 let mut __struct = Self::default();
30652 __struct.time_boot_ms = buf.get_u32_le()?;
30653 __struct.total_capacity = buf.get_f32_le()?;
30654 __struct.used_capacity = buf.get_f32_le()?;
30655 __struct.available_capacity = buf.get_f32_le()?;
30656 __struct.read_speed = buf.get_f32_le()?;
30657 __struct.write_speed = buf.get_f32_le()?;
30658 __struct.storage_id = buf.get_u8()?;
30659 __struct.storage_count = buf.get_u8()?;
30660 let tmp = buf.get_u8()?;
30661 __struct.status =
30662 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30663 enum_type: "StorageStatus",
30664 value: tmp as u64,
30665 })?;
30666 let tmp = buf.get_u8()?;
30667 __struct.mavtype =
30668 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30669 enum_type: "StorageType",
30670 value: tmp as u64,
30671 })?;
30672 let mut tmp = [0_u8; 32usize];
30673 for v in &mut tmp {
30674 *v = buf.get_u8()?;
30675 }
30676 __struct.name = CharArray::new(tmp);
30677 let tmp = buf.get_u8()?;
30678 __struct.storage_usage = StorageUsageFlag::from_bits(
30679 tmp as <StorageUsageFlag as Flags>::Bits,
30680 )
30681 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
30682 flag_type: "StorageUsageFlag",
30683 value: tmp as u64,
30684 })?;
30685 Ok(__struct)
30686 }
30687 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30688 let mut __tmp = BytesMut::new(bytes);
30689 #[allow(clippy::absurd_extreme_comparisons)]
30690 #[allow(unused_comparisons)]
30691 if __tmp.remaining() < Self::ENCODED_LEN {
30692 panic!(
30693 "buffer is too small (need {} bytes, but got {})",
30694 Self::ENCODED_LEN,
30695 __tmp.remaining(),
30696 )
30697 }
30698 __tmp.put_u32_le(self.time_boot_ms);
30699 __tmp.put_f32_le(self.total_capacity);
30700 __tmp.put_f32_le(self.used_capacity);
30701 __tmp.put_f32_le(self.available_capacity);
30702 __tmp.put_f32_le(self.read_speed);
30703 __tmp.put_f32_le(self.write_speed);
30704 __tmp.put_u8(self.storage_id);
30705 __tmp.put_u8(self.storage_count);
30706 __tmp.put_u8(self.status as u8);
30707 if matches!(version, MavlinkVersion::V2) {
30708 __tmp.put_u8(self.mavtype as u8);
30709 for val in &self.name {
30710 __tmp.put_u8(*val);
30711 }
30712 __tmp.put_u8(self.storage_usage.bits() as u8);
30713 let len = __tmp.len();
30714 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30715 } else {
30716 __tmp.len()
30717 }
30718 }
30719}
30720#[doc = "Tune formats supported by vehicle. This should be emitted as response to MAV_CMD_REQUEST_MESSAGE."]
30721#[doc = ""]
30722#[doc = "ID: 401"]
30723#[derive(Debug, Clone, PartialEq)]
30724#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30725#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30726#[cfg_attr(feature = "ts", derive(TS))]
30727#[cfg_attr(feature = "ts", ts(export))]
30728pub struct SUPPORTED_TUNES_DATA {
30729 #[doc = "Bitfield of supported tune formats."]
30730 pub format: TuneFormat,
30731 #[doc = "System ID"]
30732 pub target_system: u8,
30733 #[doc = "Component ID"]
30734 pub target_component: u8,
30735}
30736impl SUPPORTED_TUNES_DATA {
30737 pub const ENCODED_LEN: usize = 6usize;
30738 pub const DEFAULT: Self = Self {
30739 format: TuneFormat::DEFAULT,
30740 target_system: 0_u8,
30741 target_component: 0_u8,
30742 };
30743 #[cfg(feature = "arbitrary")]
30744 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30745 use arbitrary::{Arbitrary, Unstructured};
30746 let mut buf = [0u8; 1024];
30747 rng.fill_bytes(&mut buf);
30748 let mut unstructured = Unstructured::new(&buf);
30749 Self::arbitrary(&mut unstructured).unwrap_or_default()
30750 }
30751}
30752impl Default for SUPPORTED_TUNES_DATA {
30753 fn default() -> Self {
30754 Self::DEFAULT.clone()
30755 }
30756}
30757impl MessageData for SUPPORTED_TUNES_DATA {
30758 type Message = MavMessage;
30759 const ID: u32 = 401u32;
30760 const NAME: &'static str = "SUPPORTED_TUNES";
30761 const EXTRA_CRC: u8 = 183u8;
30762 const ENCODED_LEN: usize = 6usize;
30763 fn deser(
30764 _version: MavlinkVersion,
30765 __input: &[u8],
30766 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30767 let avail_len = __input.len();
30768 let mut payload_buf = [0; Self::ENCODED_LEN];
30769 let mut buf = if avail_len < Self::ENCODED_LEN {
30770 payload_buf[0..avail_len].copy_from_slice(__input);
30771 Bytes::new(&payload_buf)
30772 } else {
30773 Bytes::new(__input)
30774 };
30775 let mut __struct = Self::default();
30776 let tmp = buf.get_u32_le()?;
30777 __struct.format = FromPrimitive::from_u32(tmp).ok_or(
30778 ::mavlink_core::error::ParserError::InvalidEnum {
30779 enum_type: "TuneFormat",
30780 value: tmp as u64,
30781 },
30782 )?;
30783 __struct.target_system = buf.get_u8()?;
30784 __struct.target_component = buf.get_u8()?;
30785 Ok(__struct)
30786 }
30787 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30788 let mut __tmp = BytesMut::new(bytes);
30789 #[allow(clippy::absurd_extreme_comparisons)]
30790 #[allow(unused_comparisons)]
30791 if __tmp.remaining() < Self::ENCODED_LEN {
30792 panic!(
30793 "buffer is too small (need {} bytes, but got {})",
30794 Self::ENCODED_LEN,
30795 __tmp.remaining(),
30796 )
30797 }
30798 __tmp.put_u32_le(self.format as u32);
30799 __tmp.put_u8(self.target_system);
30800 __tmp.put_u8(self.target_component);
30801 if matches!(version, MavlinkVersion::V2) {
30802 let len = __tmp.len();
30803 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30804 } else {
30805 __tmp.len()
30806 }
30807 }
30808}
30809#[doc = "The system time is the time of the master clock. This can be emitted by flight controllers, onboard computers, or other components in the MAVLink network. Components that are using a less reliable time source, such as a battery-backed real time clock, can choose to match their system clock to that of a SYSTEM_TYPE that indicates a more recent time. This allows more broadly accurate date stamping of logs, and so on. If precise time synchronization is needed then use TIMESYNC instead."]
30810#[doc = ""]
30811#[doc = "ID: 2"]
30812#[derive(Debug, Clone, PartialEq)]
30813#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30814#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30815#[cfg_attr(feature = "ts", derive(TS))]
30816#[cfg_attr(feature = "ts", ts(export))]
30817pub struct SYSTEM_TIME_DATA {
30818 #[doc = "Timestamp (UNIX epoch time)."]
30819 pub time_unix_usec: u64,
30820 #[doc = "Timestamp (time since system boot)."]
30821 pub time_boot_ms: u32,
30822}
30823impl SYSTEM_TIME_DATA {
30824 pub const ENCODED_LEN: usize = 12usize;
30825 pub const DEFAULT: Self = Self {
30826 time_unix_usec: 0_u64,
30827 time_boot_ms: 0_u32,
30828 };
30829 #[cfg(feature = "arbitrary")]
30830 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30831 use arbitrary::{Arbitrary, Unstructured};
30832 let mut buf = [0u8; 1024];
30833 rng.fill_bytes(&mut buf);
30834 let mut unstructured = Unstructured::new(&buf);
30835 Self::arbitrary(&mut unstructured).unwrap_or_default()
30836 }
30837}
30838impl Default for SYSTEM_TIME_DATA {
30839 fn default() -> Self {
30840 Self::DEFAULT.clone()
30841 }
30842}
30843impl MessageData for SYSTEM_TIME_DATA {
30844 type Message = MavMessage;
30845 const ID: u32 = 2u32;
30846 const NAME: &'static str = "SYSTEM_TIME";
30847 const EXTRA_CRC: u8 = 137u8;
30848 const ENCODED_LEN: usize = 12usize;
30849 fn deser(
30850 _version: MavlinkVersion,
30851 __input: &[u8],
30852 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30853 let avail_len = __input.len();
30854 let mut payload_buf = [0; Self::ENCODED_LEN];
30855 let mut buf = if avail_len < Self::ENCODED_LEN {
30856 payload_buf[0..avail_len].copy_from_slice(__input);
30857 Bytes::new(&payload_buf)
30858 } else {
30859 Bytes::new(__input)
30860 };
30861 let mut __struct = Self::default();
30862 __struct.time_unix_usec = buf.get_u64_le()?;
30863 __struct.time_boot_ms = buf.get_u32_le()?;
30864 Ok(__struct)
30865 }
30866 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30867 let mut __tmp = BytesMut::new(bytes);
30868 #[allow(clippy::absurd_extreme_comparisons)]
30869 #[allow(unused_comparisons)]
30870 if __tmp.remaining() < Self::ENCODED_LEN {
30871 panic!(
30872 "buffer is too small (need {} bytes, but got {})",
30873 Self::ENCODED_LEN,
30874 __tmp.remaining(),
30875 )
30876 }
30877 __tmp.put_u64_le(self.time_unix_usec);
30878 __tmp.put_u32_le(self.time_boot_ms);
30879 if matches!(version, MavlinkVersion::V2) {
30880 let len = __tmp.len();
30881 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30882 } else {
30883 __tmp.len()
30884 }
30885 }
30886}
30887#[doc = "The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows whether the system is currently active or not and if an emergency occurred. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occurred it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout."]
30888#[doc = ""]
30889#[doc = "ID: 1"]
30890#[derive(Debug, Clone, PartialEq)]
30891#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30892#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30893#[cfg_attr(feature = "ts", derive(TS))]
30894#[cfg_attr(feature = "ts", ts(export))]
30895pub struct SYS_STATUS_DATA {
30896 #[doc = "Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present."]
30897 pub onboard_control_sensors_present: MavSysStatusSensor,
30898 #[doc = "Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled."]
30899 pub onboard_control_sensors_enabled: MavSysStatusSensor,
30900 #[doc = "Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy."]
30901 pub onboard_control_sensors_health: MavSysStatusSensor,
30902 #[doc = "Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000"]
30903 pub load: u16,
30904 #[doc = "Battery voltage, UINT16_MAX: Voltage not sent by autopilot"]
30905 pub voltage_battery: u16,
30906 #[doc = "Battery current, -1: Current not sent by autopilot"]
30907 pub current_battery: i16,
30908 #[doc = "Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)"]
30909 pub drop_rate_comm: u16,
30910 #[doc = "Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)"]
30911 pub errors_comm: u16,
30912 #[doc = "Autopilot-specific errors"]
30913 pub errors_count1: u16,
30914 #[doc = "Autopilot-specific errors"]
30915 pub errors_count2: u16,
30916 #[doc = "Autopilot-specific errors"]
30917 pub errors_count3: u16,
30918 #[doc = "Autopilot-specific errors"]
30919 pub errors_count4: u16,
30920 #[doc = "Battery energy remaining, -1: Battery remaining energy not sent by autopilot"]
30921 pub battery_remaining: i8,
30922 #[doc = "Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present."]
30923 #[cfg_attr(feature = "serde", serde(default))]
30924 pub onboard_control_sensors_present_extended: MavSysStatusSensorExtended,
30925 #[doc = "Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled."]
30926 #[cfg_attr(feature = "serde", serde(default))]
30927 pub onboard_control_sensors_enabled_extended: MavSysStatusSensorExtended,
30928 #[doc = "Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy."]
30929 #[cfg_attr(feature = "serde", serde(default))]
30930 pub onboard_control_sensors_health_extended: MavSysStatusSensorExtended,
30931}
30932impl SYS_STATUS_DATA {
30933 pub const ENCODED_LEN: usize = 43usize;
30934 pub const DEFAULT: Self = Self {
30935 onboard_control_sensors_present: MavSysStatusSensor::DEFAULT,
30936 onboard_control_sensors_enabled: MavSysStatusSensor::DEFAULT,
30937 onboard_control_sensors_health: MavSysStatusSensor::DEFAULT,
30938 load: 0_u16,
30939 voltage_battery: 0_u16,
30940 current_battery: 0_i16,
30941 drop_rate_comm: 0_u16,
30942 errors_comm: 0_u16,
30943 errors_count1: 0_u16,
30944 errors_count2: 0_u16,
30945 errors_count3: 0_u16,
30946 errors_count4: 0_u16,
30947 battery_remaining: 0_i8,
30948 onboard_control_sensors_present_extended: MavSysStatusSensorExtended::DEFAULT,
30949 onboard_control_sensors_enabled_extended: MavSysStatusSensorExtended::DEFAULT,
30950 onboard_control_sensors_health_extended: MavSysStatusSensorExtended::DEFAULT,
30951 };
30952 #[cfg(feature = "arbitrary")]
30953 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30954 use arbitrary::{Arbitrary, Unstructured};
30955 let mut buf = [0u8; 1024];
30956 rng.fill_bytes(&mut buf);
30957 let mut unstructured = Unstructured::new(&buf);
30958 Self::arbitrary(&mut unstructured).unwrap_or_default()
30959 }
30960}
30961impl Default for SYS_STATUS_DATA {
30962 fn default() -> Self {
30963 Self::DEFAULT.clone()
30964 }
30965}
30966impl MessageData for SYS_STATUS_DATA {
30967 type Message = MavMessage;
30968 const ID: u32 = 1u32;
30969 const NAME: &'static str = "SYS_STATUS";
30970 const EXTRA_CRC: u8 = 124u8;
30971 const ENCODED_LEN: usize = 43usize;
30972 fn deser(
30973 _version: MavlinkVersion,
30974 __input: &[u8],
30975 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30976 let avail_len = __input.len();
30977 let mut payload_buf = [0; Self::ENCODED_LEN];
30978 let mut buf = if avail_len < Self::ENCODED_LEN {
30979 payload_buf[0..avail_len].copy_from_slice(__input);
30980 Bytes::new(&payload_buf)
30981 } else {
30982 Bytes::new(__input)
30983 };
30984 let mut __struct = Self::default();
30985 let tmp = buf.get_u32_le()?;
30986 __struct.onboard_control_sensors_present = MavSysStatusSensor::from_bits(
30987 tmp as <MavSysStatusSensor as Flags>::Bits,
30988 )
30989 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
30990 flag_type: "MavSysStatusSensor",
30991 value: tmp as u64,
30992 })?;
30993 let tmp = buf.get_u32_le()?;
30994 __struct.onboard_control_sensors_enabled = MavSysStatusSensor::from_bits(
30995 tmp as <MavSysStatusSensor as Flags>::Bits,
30996 )
30997 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
30998 flag_type: "MavSysStatusSensor",
30999 value: tmp as u64,
31000 })?;
31001 let tmp = buf.get_u32_le()?;
31002 __struct.onboard_control_sensors_health = MavSysStatusSensor::from_bits(
31003 tmp as <MavSysStatusSensor as Flags>::Bits,
31004 )
31005 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
31006 flag_type: "MavSysStatusSensor",
31007 value: tmp as u64,
31008 })?;
31009 __struct.load = buf.get_u16_le()?;
31010 __struct.voltage_battery = buf.get_u16_le()?;
31011 __struct.current_battery = buf.get_i16_le()?;
31012 __struct.drop_rate_comm = buf.get_u16_le()?;
31013 __struct.errors_comm = buf.get_u16_le()?;
31014 __struct.errors_count1 = buf.get_u16_le()?;
31015 __struct.errors_count2 = buf.get_u16_le()?;
31016 __struct.errors_count3 = buf.get_u16_le()?;
31017 __struct.errors_count4 = buf.get_u16_le()?;
31018 __struct.battery_remaining = buf.get_i8()?;
31019 let tmp = buf.get_u32_le()?;
31020 __struct.onboard_control_sensors_present_extended = MavSysStatusSensorExtended::from_bits(
31021 tmp as <MavSysStatusSensorExtended as Flags>::Bits,
31022 )
31023 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
31024 flag_type: "MavSysStatusSensorExtended",
31025 value: tmp as u64,
31026 })?;
31027 let tmp = buf.get_u32_le()?;
31028 __struct.onboard_control_sensors_enabled_extended = MavSysStatusSensorExtended::from_bits(
31029 tmp as <MavSysStatusSensorExtended as Flags>::Bits,
31030 )
31031 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
31032 flag_type: "MavSysStatusSensorExtended",
31033 value: tmp as u64,
31034 })?;
31035 let tmp = buf.get_u32_le()?;
31036 __struct.onboard_control_sensors_health_extended = MavSysStatusSensorExtended::from_bits(
31037 tmp as <MavSysStatusSensorExtended as Flags>::Bits,
31038 )
31039 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
31040 flag_type: "MavSysStatusSensorExtended",
31041 value: tmp as u64,
31042 })?;
31043 Ok(__struct)
31044 }
31045 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31046 let mut __tmp = BytesMut::new(bytes);
31047 #[allow(clippy::absurd_extreme_comparisons)]
31048 #[allow(unused_comparisons)]
31049 if __tmp.remaining() < Self::ENCODED_LEN {
31050 panic!(
31051 "buffer is too small (need {} bytes, but got {})",
31052 Self::ENCODED_LEN,
31053 __tmp.remaining(),
31054 )
31055 }
31056 __tmp.put_u32_le(self.onboard_control_sensors_present.bits() as u32);
31057 __tmp.put_u32_le(self.onboard_control_sensors_enabled.bits() as u32);
31058 __tmp.put_u32_le(self.onboard_control_sensors_health.bits() as u32);
31059 __tmp.put_u16_le(self.load);
31060 __tmp.put_u16_le(self.voltage_battery);
31061 __tmp.put_i16_le(self.current_battery);
31062 __tmp.put_u16_le(self.drop_rate_comm);
31063 __tmp.put_u16_le(self.errors_comm);
31064 __tmp.put_u16_le(self.errors_count1);
31065 __tmp.put_u16_le(self.errors_count2);
31066 __tmp.put_u16_le(self.errors_count3);
31067 __tmp.put_u16_le(self.errors_count4);
31068 __tmp.put_i8(self.battery_remaining);
31069 if matches!(version, MavlinkVersion::V2) {
31070 __tmp.put_u32_le(self.onboard_control_sensors_present_extended.bits() as u32);
31071 __tmp.put_u32_le(self.onboard_control_sensors_enabled_extended.bits() as u32);
31072 __tmp.put_u32_le(self.onboard_control_sensors_health_extended.bits() as u32);
31073 let len = __tmp.len();
31074 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31075 } else {
31076 __tmp.len()
31077 }
31078 }
31079}
31080#[doc = "Request that the vehicle report terrain height at the given location (expected response is a TERRAIN_REPORT). Used by GCS to check if vehicle has all terrain data needed for a mission."]
31081#[doc = ""]
31082#[doc = "ID: 135"]
31083#[derive(Debug, Clone, PartialEq)]
31084#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31085#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31086#[cfg_attr(feature = "ts", derive(TS))]
31087#[cfg_attr(feature = "ts", ts(export))]
31088pub struct TERRAIN_CHECK_DATA {
31089 #[doc = "Latitude"]
31090 pub lat: i32,
31091 #[doc = "Longitude"]
31092 pub lon: i32,
31093}
31094impl TERRAIN_CHECK_DATA {
31095 pub const ENCODED_LEN: usize = 8usize;
31096 pub const DEFAULT: Self = Self {
31097 lat: 0_i32,
31098 lon: 0_i32,
31099 };
31100 #[cfg(feature = "arbitrary")]
31101 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31102 use arbitrary::{Arbitrary, Unstructured};
31103 let mut buf = [0u8; 1024];
31104 rng.fill_bytes(&mut buf);
31105 let mut unstructured = Unstructured::new(&buf);
31106 Self::arbitrary(&mut unstructured).unwrap_or_default()
31107 }
31108}
31109impl Default for TERRAIN_CHECK_DATA {
31110 fn default() -> Self {
31111 Self::DEFAULT.clone()
31112 }
31113}
31114impl MessageData for TERRAIN_CHECK_DATA {
31115 type Message = MavMessage;
31116 const ID: u32 = 135u32;
31117 const NAME: &'static str = "TERRAIN_CHECK";
31118 const EXTRA_CRC: u8 = 203u8;
31119 const ENCODED_LEN: usize = 8usize;
31120 fn deser(
31121 _version: MavlinkVersion,
31122 __input: &[u8],
31123 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31124 let avail_len = __input.len();
31125 let mut payload_buf = [0; Self::ENCODED_LEN];
31126 let mut buf = if avail_len < Self::ENCODED_LEN {
31127 payload_buf[0..avail_len].copy_from_slice(__input);
31128 Bytes::new(&payload_buf)
31129 } else {
31130 Bytes::new(__input)
31131 };
31132 let mut __struct = Self::default();
31133 __struct.lat = buf.get_i32_le()?;
31134 __struct.lon = buf.get_i32_le()?;
31135 Ok(__struct)
31136 }
31137 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31138 let mut __tmp = BytesMut::new(bytes);
31139 #[allow(clippy::absurd_extreme_comparisons)]
31140 #[allow(unused_comparisons)]
31141 if __tmp.remaining() < Self::ENCODED_LEN {
31142 panic!(
31143 "buffer is too small (need {} bytes, but got {})",
31144 Self::ENCODED_LEN,
31145 __tmp.remaining(),
31146 )
31147 }
31148 __tmp.put_i32_le(self.lat);
31149 __tmp.put_i32_le(self.lon);
31150 if matches!(version, MavlinkVersion::V2) {
31151 let len = __tmp.len();
31152 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31153 } else {
31154 __tmp.len()
31155 }
31156 }
31157}
31158#[doc = "Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST. See terrain protocol docs: <https://mavlink.io/en/services/terrain.html>."]
31159#[doc = ""]
31160#[doc = "ID: 134"]
31161#[derive(Debug, Clone, PartialEq)]
31162#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31163#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31164#[cfg_attr(feature = "ts", derive(TS))]
31165#[cfg_attr(feature = "ts", ts(export))]
31166pub struct TERRAIN_DATA_DATA {
31167 #[doc = "Latitude of SW corner of first grid"]
31168 pub lat: i32,
31169 #[doc = "Longitude of SW corner of first grid"]
31170 pub lon: i32,
31171 #[doc = "Grid spacing"]
31172 pub grid_spacing: u16,
31173 #[doc = "Terrain data MSL"]
31174 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31175 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
31176 pub data: [i16; 16],
31177 #[doc = "bit within the terrain request mask"]
31178 pub gridbit: u8,
31179}
31180impl TERRAIN_DATA_DATA {
31181 pub const ENCODED_LEN: usize = 43usize;
31182 pub const DEFAULT: Self = Self {
31183 lat: 0_i32,
31184 lon: 0_i32,
31185 grid_spacing: 0_u16,
31186 data: [0_i16; 16usize],
31187 gridbit: 0_u8,
31188 };
31189 #[cfg(feature = "arbitrary")]
31190 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31191 use arbitrary::{Arbitrary, Unstructured};
31192 let mut buf = [0u8; 1024];
31193 rng.fill_bytes(&mut buf);
31194 let mut unstructured = Unstructured::new(&buf);
31195 Self::arbitrary(&mut unstructured).unwrap_or_default()
31196 }
31197}
31198impl Default for TERRAIN_DATA_DATA {
31199 fn default() -> Self {
31200 Self::DEFAULT.clone()
31201 }
31202}
31203impl MessageData for TERRAIN_DATA_DATA {
31204 type Message = MavMessage;
31205 const ID: u32 = 134u32;
31206 const NAME: &'static str = "TERRAIN_DATA";
31207 const EXTRA_CRC: u8 = 229u8;
31208 const ENCODED_LEN: usize = 43usize;
31209 fn deser(
31210 _version: MavlinkVersion,
31211 __input: &[u8],
31212 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31213 let avail_len = __input.len();
31214 let mut payload_buf = [0; Self::ENCODED_LEN];
31215 let mut buf = if avail_len < Self::ENCODED_LEN {
31216 payload_buf[0..avail_len].copy_from_slice(__input);
31217 Bytes::new(&payload_buf)
31218 } else {
31219 Bytes::new(__input)
31220 };
31221 let mut __struct = Self::default();
31222 __struct.lat = buf.get_i32_le()?;
31223 __struct.lon = buf.get_i32_le()?;
31224 __struct.grid_spacing = buf.get_u16_le()?;
31225 for v in &mut __struct.data {
31226 let val = buf.get_i16_le()?;
31227 *v = val;
31228 }
31229 __struct.gridbit = buf.get_u8()?;
31230 Ok(__struct)
31231 }
31232 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31233 let mut __tmp = BytesMut::new(bytes);
31234 #[allow(clippy::absurd_extreme_comparisons)]
31235 #[allow(unused_comparisons)]
31236 if __tmp.remaining() < Self::ENCODED_LEN {
31237 panic!(
31238 "buffer is too small (need {} bytes, but got {})",
31239 Self::ENCODED_LEN,
31240 __tmp.remaining(),
31241 )
31242 }
31243 __tmp.put_i32_le(self.lat);
31244 __tmp.put_i32_le(self.lon);
31245 __tmp.put_u16_le(self.grid_spacing);
31246 for val in &self.data {
31247 __tmp.put_i16_le(*val);
31248 }
31249 __tmp.put_u8(self.gridbit);
31250 if matches!(version, MavlinkVersion::V2) {
31251 let len = __tmp.len();
31252 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31253 } else {
31254 __tmp.len()
31255 }
31256 }
31257}
31258#[doc = "Streamed from drone to report progress of terrain map download (initiated by TERRAIN_REQUEST), or sent as a response to a TERRAIN_CHECK request. See terrain protocol docs: <https://mavlink.io/en/services/terrain.html>."]
31259#[doc = ""]
31260#[doc = "ID: 136"]
31261#[derive(Debug, Clone, PartialEq)]
31262#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31263#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31264#[cfg_attr(feature = "ts", derive(TS))]
31265#[cfg_attr(feature = "ts", ts(export))]
31266pub struct TERRAIN_REPORT_DATA {
31267 #[doc = "Latitude"]
31268 pub lat: i32,
31269 #[doc = "Longitude"]
31270 pub lon: i32,
31271 #[doc = "Terrain height MSL"]
31272 pub terrain_height: f32,
31273 #[doc = "Current vehicle height above lat/lon terrain height"]
31274 pub current_height: f32,
31275 #[doc = "grid spacing (zero if terrain at this location unavailable)"]
31276 pub spacing: u16,
31277 #[doc = "Number of 4x4 terrain blocks waiting to be received or read from disk"]
31278 pub pending: u16,
31279 #[doc = "Number of 4x4 terrain blocks in memory"]
31280 pub loaded: u16,
31281}
31282impl TERRAIN_REPORT_DATA {
31283 pub const ENCODED_LEN: usize = 22usize;
31284 pub const DEFAULT: Self = Self {
31285 lat: 0_i32,
31286 lon: 0_i32,
31287 terrain_height: 0.0_f32,
31288 current_height: 0.0_f32,
31289 spacing: 0_u16,
31290 pending: 0_u16,
31291 loaded: 0_u16,
31292 };
31293 #[cfg(feature = "arbitrary")]
31294 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31295 use arbitrary::{Arbitrary, Unstructured};
31296 let mut buf = [0u8; 1024];
31297 rng.fill_bytes(&mut buf);
31298 let mut unstructured = Unstructured::new(&buf);
31299 Self::arbitrary(&mut unstructured).unwrap_or_default()
31300 }
31301}
31302impl Default for TERRAIN_REPORT_DATA {
31303 fn default() -> Self {
31304 Self::DEFAULT.clone()
31305 }
31306}
31307impl MessageData for TERRAIN_REPORT_DATA {
31308 type Message = MavMessage;
31309 const ID: u32 = 136u32;
31310 const NAME: &'static str = "TERRAIN_REPORT";
31311 const EXTRA_CRC: u8 = 1u8;
31312 const ENCODED_LEN: usize = 22usize;
31313 fn deser(
31314 _version: MavlinkVersion,
31315 __input: &[u8],
31316 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31317 let avail_len = __input.len();
31318 let mut payload_buf = [0; Self::ENCODED_LEN];
31319 let mut buf = if avail_len < Self::ENCODED_LEN {
31320 payload_buf[0..avail_len].copy_from_slice(__input);
31321 Bytes::new(&payload_buf)
31322 } else {
31323 Bytes::new(__input)
31324 };
31325 let mut __struct = Self::default();
31326 __struct.lat = buf.get_i32_le()?;
31327 __struct.lon = buf.get_i32_le()?;
31328 __struct.terrain_height = buf.get_f32_le()?;
31329 __struct.current_height = buf.get_f32_le()?;
31330 __struct.spacing = buf.get_u16_le()?;
31331 __struct.pending = buf.get_u16_le()?;
31332 __struct.loaded = buf.get_u16_le()?;
31333 Ok(__struct)
31334 }
31335 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31336 let mut __tmp = BytesMut::new(bytes);
31337 #[allow(clippy::absurd_extreme_comparisons)]
31338 #[allow(unused_comparisons)]
31339 if __tmp.remaining() < Self::ENCODED_LEN {
31340 panic!(
31341 "buffer is too small (need {} bytes, but got {})",
31342 Self::ENCODED_LEN,
31343 __tmp.remaining(),
31344 )
31345 }
31346 __tmp.put_i32_le(self.lat);
31347 __tmp.put_i32_le(self.lon);
31348 __tmp.put_f32_le(self.terrain_height);
31349 __tmp.put_f32_le(self.current_height);
31350 __tmp.put_u16_le(self.spacing);
31351 __tmp.put_u16_le(self.pending);
31352 __tmp.put_u16_le(self.loaded);
31353 if matches!(version, MavlinkVersion::V2) {
31354 let len = __tmp.len();
31355 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31356 } else {
31357 __tmp.len()
31358 }
31359 }
31360}
31361#[doc = "Request for terrain data and terrain status. See terrain protocol docs: <https://mavlink.io/en/services/terrain.html>."]
31362#[doc = ""]
31363#[doc = "ID: 133"]
31364#[derive(Debug, Clone, PartialEq)]
31365#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31366#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31367#[cfg_attr(feature = "ts", derive(TS))]
31368#[cfg_attr(feature = "ts", ts(export))]
31369pub struct TERRAIN_REQUEST_DATA {
31370 #[doc = "Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)"]
31371 pub mask: u64,
31372 #[doc = "Latitude of SW corner of first grid"]
31373 pub lat: i32,
31374 #[doc = "Longitude of SW corner of first grid"]
31375 pub lon: i32,
31376 #[doc = "Grid spacing"]
31377 pub grid_spacing: u16,
31378}
31379impl TERRAIN_REQUEST_DATA {
31380 pub const ENCODED_LEN: usize = 18usize;
31381 pub const DEFAULT: Self = Self {
31382 mask: 0_u64,
31383 lat: 0_i32,
31384 lon: 0_i32,
31385 grid_spacing: 0_u16,
31386 };
31387 #[cfg(feature = "arbitrary")]
31388 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31389 use arbitrary::{Arbitrary, Unstructured};
31390 let mut buf = [0u8; 1024];
31391 rng.fill_bytes(&mut buf);
31392 let mut unstructured = Unstructured::new(&buf);
31393 Self::arbitrary(&mut unstructured).unwrap_or_default()
31394 }
31395}
31396impl Default for TERRAIN_REQUEST_DATA {
31397 fn default() -> Self {
31398 Self::DEFAULT.clone()
31399 }
31400}
31401impl MessageData for TERRAIN_REQUEST_DATA {
31402 type Message = MavMessage;
31403 const ID: u32 = 133u32;
31404 const NAME: &'static str = "TERRAIN_REQUEST";
31405 const EXTRA_CRC: u8 = 6u8;
31406 const ENCODED_LEN: usize = 18usize;
31407 fn deser(
31408 _version: MavlinkVersion,
31409 __input: &[u8],
31410 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31411 let avail_len = __input.len();
31412 let mut payload_buf = [0; Self::ENCODED_LEN];
31413 let mut buf = if avail_len < Self::ENCODED_LEN {
31414 payload_buf[0..avail_len].copy_from_slice(__input);
31415 Bytes::new(&payload_buf)
31416 } else {
31417 Bytes::new(__input)
31418 };
31419 let mut __struct = Self::default();
31420 __struct.mask = buf.get_u64_le()?;
31421 __struct.lat = buf.get_i32_le()?;
31422 __struct.lon = buf.get_i32_le()?;
31423 __struct.grid_spacing = buf.get_u16_le()?;
31424 Ok(__struct)
31425 }
31426 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31427 let mut __tmp = BytesMut::new(bytes);
31428 #[allow(clippy::absurd_extreme_comparisons)]
31429 #[allow(unused_comparisons)]
31430 if __tmp.remaining() < Self::ENCODED_LEN {
31431 panic!(
31432 "buffer is too small (need {} bytes, but got {})",
31433 Self::ENCODED_LEN,
31434 __tmp.remaining(),
31435 )
31436 }
31437 __tmp.put_u64_le(self.mask);
31438 __tmp.put_i32_le(self.lat);
31439 __tmp.put_i32_le(self.lon);
31440 __tmp.put_u16_le(self.grid_spacing);
31441 if matches!(version, MavlinkVersion::V2) {
31442 let len = __tmp.len();
31443 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31444 } else {
31445 __tmp.len()
31446 }
31447 }
31448}
31449#[doc = "Time synchronization message. The message is used for both timesync requests and responses. The request is sent with `ts1=syncing component timestamp` and `tc1=0`, and may be broadcast or targeted to a specific system/component. The response is sent with `ts1=syncing component timestamp` (mirror back unchanged), and `tc1=responding component timestamp`, with the `target_system` and `target_component` set to ids of the original request. Systems can determine if they are receiving a request or response based on the value of `tc`. If the response has `target_system==target_component==0` the remote system has not been updated to use the component IDs and cannot reliably timesync; the requestor may report an error. Timestamps are UNIX Epoch time or time since system boot in nanoseconds (the timestamp format can be inferred by checking for the magnitude of the number; generally it doesn't matter as only the offset is used). The message sequence is repeated numerous times with results being filtered/averaged to estimate the offset. See also: <https://mavlink.io/en/services/timesync.html>."]
31450#[doc = ""]
31451#[doc = "ID: 111"]
31452#[derive(Debug, Clone, PartialEq)]
31453#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31454#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31455#[cfg_attr(feature = "ts", derive(TS))]
31456#[cfg_attr(feature = "ts", ts(export))]
31457pub struct TIMESYNC_DATA {
31458 #[doc = "Time sync timestamp 1. Syncing: 0. Responding: Timestamp of responding component."]
31459 pub tc1: i64,
31460 #[doc = "Time sync timestamp 2. Timestamp of syncing component (mirrored in response)."]
31461 pub ts1: i64,
31462 #[doc = "Target system id. Request: 0 (broadcast) or id of specific system. Response must contain system id of the requesting component."]
31463 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
31464 pub target_system: u8,
31465 #[doc = "Target component id. Request: 0 (broadcast) or id of specific component. Response must contain component id of the requesting component."]
31466 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
31467 pub target_component: u8,
31468}
31469impl TIMESYNC_DATA {
31470 pub const ENCODED_LEN: usize = 18usize;
31471 pub const DEFAULT: Self = Self {
31472 tc1: 0_i64,
31473 ts1: 0_i64,
31474 target_system: 0_u8,
31475 target_component: 0_u8,
31476 };
31477 #[cfg(feature = "arbitrary")]
31478 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31479 use arbitrary::{Arbitrary, Unstructured};
31480 let mut buf = [0u8; 1024];
31481 rng.fill_bytes(&mut buf);
31482 let mut unstructured = Unstructured::new(&buf);
31483 Self::arbitrary(&mut unstructured).unwrap_or_default()
31484 }
31485}
31486impl Default for TIMESYNC_DATA {
31487 fn default() -> Self {
31488 Self::DEFAULT.clone()
31489 }
31490}
31491impl MessageData for TIMESYNC_DATA {
31492 type Message = MavMessage;
31493 const ID: u32 = 111u32;
31494 const NAME: &'static str = "TIMESYNC";
31495 const EXTRA_CRC: u8 = 34u8;
31496 const ENCODED_LEN: usize = 18usize;
31497 fn deser(
31498 _version: MavlinkVersion,
31499 __input: &[u8],
31500 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31501 let avail_len = __input.len();
31502 let mut payload_buf = [0; Self::ENCODED_LEN];
31503 let mut buf = if avail_len < Self::ENCODED_LEN {
31504 payload_buf[0..avail_len].copy_from_slice(__input);
31505 Bytes::new(&payload_buf)
31506 } else {
31507 Bytes::new(__input)
31508 };
31509 let mut __struct = Self::default();
31510 __struct.tc1 = buf.get_i64_le()?;
31511 __struct.ts1 = buf.get_i64_le()?;
31512 __struct.target_system = buf.get_u8()?;
31513 __struct.target_component = buf.get_u8()?;
31514 Ok(__struct)
31515 }
31516 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31517 let mut __tmp = BytesMut::new(bytes);
31518 #[allow(clippy::absurd_extreme_comparisons)]
31519 #[allow(unused_comparisons)]
31520 if __tmp.remaining() < Self::ENCODED_LEN {
31521 panic!(
31522 "buffer is too small (need {} bytes, but got {})",
31523 Self::ENCODED_LEN,
31524 __tmp.remaining(),
31525 )
31526 }
31527 __tmp.put_i64_le(self.tc1);
31528 __tmp.put_i64_le(self.ts1);
31529 if matches!(version, MavlinkVersion::V2) {
31530 __tmp.put_u8(self.target_system);
31531 __tmp.put_u8(self.target_component);
31532 let len = __tmp.len();
31533 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31534 } else {
31535 __tmp.len()
31536 }
31537 }
31538}
31539#[doc = "Time/duration estimates for various events and actions given the current vehicle state and position."]
31540#[doc = ""]
31541#[doc = "ID: 380"]
31542#[derive(Debug, Clone, PartialEq)]
31543#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31544#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31545#[cfg_attr(feature = "ts", derive(TS))]
31546#[cfg_attr(feature = "ts", ts(export))]
31547pub struct TIME_ESTIMATE_TO_TARGET_DATA {
31548 #[doc = "Estimated time to complete the vehicle's configured \"safe return\" action from its current position (e.g. RTL, Smart RTL, etc.). -1 indicates that the vehicle is landed, or that no time estimate available."]
31549 pub safe_return: i32,
31550 #[doc = "Estimated time for vehicle to complete the LAND action from its current position. -1 indicates that the vehicle is landed, or that no time estimate available."]
31551 pub land: i32,
31552 #[doc = "Estimated time for reaching/completing the currently active mission item. -1 means no time estimate available."]
31553 pub mission_next_item: i32,
31554 #[doc = "Estimated time for completing the current mission. -1 means no mission active and/or no estimate available."]
31555 pub mission_end: i32,
31556 #[doc = "Estimated time for completing the current commanded action (i.e. Go To, Takeoff, Land, etc.). -1 means no action active and/or no estimate available."]
31557 pub commanded_action: i32,
31558}
31559impl TIME_ESTIMATE_TO_TARGET_DATA {
31560 pub const ENCODED_LEN: usize = 20usize;
31561 pub const DEFAULT: Self = Self {
31562 safe_return: 0_i32,
31563 land: 0_i32,
31564 mission_next_item: 0_i32,
31565 mission_end: 0_i32,
31566 commanded_action: 0_i32,
31567 };
31568 #[cfg(feature = "arbitrary")]
31569 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31570 use arbitrary::{Arbitrary, Unstructured};
31571 let mut buf = [0u8; 1024];
31572 rng.fill_bytes(&mut buf);
31573 let mut unstructured = Unstructured::new(&buf);
31574 Self::arbitrary(&mut unstructured).unwrap_or_default()
31575 }
31576}
31577impl Default for TIME_ESTIMATE_TO_TARGET_DATA {
31578 fn default() -> Self {
31579 Self::DEFAULT.clone()
31580 }
31581}
31582impl MessageData for TIME_ESTIMATE_TO_TARGET_DATA {
31583 type Message = MavMessage;
31584 const ID: u32 = 380u32;
31585 const NAME: &'static str = "TIME_ESTIMATE_TO_TARGET";
31586 const EXTRA_CRC: u8 = 232u8;
31587 const ENCODED_LEN: usize = 20usize;
31588 fn deser(
31589 _version: MavlinkVersion,
31590 __input: &[u8],
31591 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31592 let avail_len = __input.len();
31593 let mut payload_buf = [0; Self::ENCODED_LEN];
31594 let mut buf = if avail_len < Self::ENCODED_LEN {
31595 payload_buf[0..avail_len].copy_from_slice(__input);
31596 Bytes::new(&payload_buf)
31597 } else {
31598 Bytes::new(__input)
31599 };
31600 let mut __struct = Self::default();
31601 __struct.safe_return = buf.get_i32_le()?;
31602 __struct.land = buf.get_i32_le()?;
31603 __struct.mission_next_item = buf.get_i32_le()?;
31604 __struct.mission_end = buf.get_i32_le()?;
31605 __struct.commanded_action = buf.get_i32_le()?;
31606 Ok(__struct)
31607 }
31608 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31609 let mut __tmp = BytesMut::new(bytes);
31610 #[allow(clippy::absurd_extreme_comparisons)]
31611 #[allow(unused_comparisons)]
31612 if __tmp.remaining() < Self::ENCODED_LEN {
31613 panic!(
31614 "buffer is too small (need {} bytes, but got {})",
31615 Self::ENCODED_LEN,
31616 __tmp.remaining(),
31617 )
31618 }
31619 __tmp.put_i32_le(self.safe_return);
31620 __tmp.put_i32_le(self.land);
31621 __tmp.put_i32_le(self.mission_next_item);
31622 __tmp.put_i32_le(self.mission_end);
31623 __tmp.put_i32_le(self.commanded_action);
31624 if matches!(version, MavlinkVersion::V2) {
31625 let len = __tmp.len();
31626 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31627 } else {
31628 __tmp.len()
31629 }
31630 }
31631}
31632#[doc = "Describe a trajectory using an array of up-to 5 bezier control points in the local frame (MAV_FRAME_LOCAL_NED)."]
31633#[doc = ""]
31634#[doc = "ID: 333"]
31635#[derive(Debug, Clone, PartialEq)]
31636#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31637#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31638#[cfg_attr(feature = "ts", derive(TS))]
31639#[cfg_attr(feature = "ts", ts(export))]
31640pub struct TRAJECTORY_REPRESENTATION_BEZIER_DATA {
31641 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
31642 pub time_usec: u64,
31643 #[doc = "X-coordinate of bezier control points. Set to NaN if not being used"]
31644 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31645 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
31646 pub pos_x: [f32; 5],
31647 #[doc = "Y-coordinate of bezier control points. Set to NaN if not being used"]
31648 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31649 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
31650 pub pos_y: [f32; 5],
31651 #[doc = "Z-coordinate of bezier control points. Set to NaN if not being used"]
31652 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31653 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
31654 pub pos_z: [f32; 5],
31655 #[doc = "Bezier time horizon. Set to NaN if velocity/acceleration should not be incorporated"]
31656 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31657 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
31658 pub delta: [f32; 5],
31659 #[doc = "Yaw. Set to NaN for unchanged"]
31660 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31661 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
31662 pub pos_yaw: [f32; 5],
31663 #[doc = "Number of valid control points (up-to 5 points are possible)"]
31664 pub valid_points: u8,
31665}
31666impl TRAJECTORY_REPRESENTATION_BEZIER_DATA {
31667 pub const ENCODED_LEN: usize = 109usize;
31668 pub const DEFAULT: Self = Self {
31669 time_usec: 0_u64,
31670 pos_x: [0.0_f32; 5usize],
31671 pos_y: [0.0_f32; 5usize],
31672 pos_z: [0.0_f32; 5usize],
31673 delta: [0.0_f32; 5usize],
31674 pos_yaw: [0.0_f32; 5usize],
31675 valid_points: 0_u8,
31676 };
31677 #[cfg(feature = "arbitrary")]
31678 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31679 use arbitrary::{Arbitrary, Unstructured};
31680 let mut buf = [0u8; 1024];
31681 rng.fill_bytes(&mut buf);
31682 let mut unstructured = Unstructured::new(&buf);
31683 Self::arbitrary(&mut unstructured).unwrap_or_default()
31684 }
31685}
31686impl Default for TRAJECTORY_REPRESENTATION_BEZIER_DATA {
31687 fn default() -> Self {
31688 Self::DEFAULT.clone()
31689 }
31690}
31691impl MessageData for TRAJECTORY_REPRESENTATION_BEZIER_DATA {
31692 type Message = MavMessage;
31693 const ID: u32 = 333u32;
31694 const NAME: &'static str = "TRAJECTORY_REPRESENTATION_BEZIER";
31695 const EXTRA_CRC: u8 = 231u8;
31696 const ENCODED_LEN: usize = 109usize;
31697 fn deser(
31698 _version: MavlinkVersion,
31699 __input: &[u8],
31700 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31701 let avail_len = __input.len();
31702 let mut payload_buf = [0; Self::ENCODED_LEN];
31703 let mut buf = if avail_len < Self::ENCODED_LEN {
31704 payload_buf[0..avail_len].copy_from_slice(__input);
31705 Bytes::new(&payload_buf)
31706 } else {
31707 Bytes::new(__input)
31708 };
31709 let mut __struct = Self::default();
31710 __struct.time_usec = buf.get_u64_le()?;
31711 for v in &mut __struct.pos_x {
31712 let val = buf.get_f32_le()?;
31713 *v = val;
31714 }
31715 for v in &mut __struct.pos_y {
31716 let val = buf.get_f32_le()?;
31717 *v = val;
31718 }
31719 for v in &mut __struct.pos_z {
31720 let val = buf.get_f32_le()?;
31721 *v = val;
31722 }
31723 for v in &mut __struct.delta {
31724 let val = buf.get_f32_le()?;
31725 *v = val;
31726 }
31727 for v in &mut __struct.pos_yaw {
31728 let val = buf.get_f32_le()?;
31729 *v = val;
31730 }
31731 __struct.valid_points = buf.get_u8()?;
31732 Ok(__struct)
31733 }
31734 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31735 let mut __tmp = BytesMut::new(bytes);
31736 #[allow(clippy::absurd_extreme_comparisons)]
31737 #[allow(unused_comparisons)]
31738 if __tmp.remaining() < Self::ENCODED_LEN {
31739 panic!(
31740 "buffer is too small (need {} bytes, but got {})",
31741 Self::ENCODED_LEN,
31742 __tmp.remaining(),
31743 )
31744 }
31745 __tmp.put_u64_le(self.time_usec);
31746 for val in &self.pos_x {
31747 __tmp.put_f32_le(*val);
31748 }
31749 for val in &self.pos_y {
31750 __tmp.put_f32_le(*val);
31751 }
31752 for val in &self.pos_z {
31753 __tmp.put_f32_le(*val);
31754 }
31755 for val in &self.delta {
31756 __tmp.put_f32_le(*val);
31757 }
31758 for val in &self.pos_yaw {
31759 __tmp.put_f32_le(*val);
31760 }
31761 __tmp.put_u8(self.valid_points);
31762 if matches!(version, MavlinkVersion::V2) {
31763 let len = __tmp.len();
31764 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31765 } else {
31766 __tmp.len()
31767 }
31768 }
31769}
31770#[doc = "Describe a trajectory using an array of up-to 5 waypoints in the local frame (MAV_FRAME_LOCAL_NED)."]
31771#[doc = ""]
31772#[doc = "ID: 332"]
31773#[derive(Debug, Clone, PartialEq)]
31774#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31775#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31776#[cfg_attr(feature = "ts", derive(TS))]
31777#[cfg_attr(feature = "ts", ts(export))]
31778pub struct TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA {
31779 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
31780 pub time_usec: u64,
31781 #[doc = "X-coordinate of waypoint, set to NaN if not being used"]
31782 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31783 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
31784 pub pos_x: [f32; 5],
31785 #[doc = "Y-coordinate of waypoint, set to NaN if not being used"]
31786 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31787 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
31788 pub pos_y: [f32; 5],
31789 #[doc = "Z-coordinate of waypoint, set to NaN if not being used"]
31790 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31791 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
31792 pub pos_z: [f32; 5],
31793 #[doc = "X-velocity of waypoint, set to NaN if not being used"]
31794 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31795 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
31796 pub vel_x: [f32; 5],
31797 #[doc = "Y-velocity of waypoint, set to NaN if not being used"]
31798 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31799 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
31800 pub vel_y: [f32; 5],
31801 #[doc = "Z-velocity of waypoint, set to NaN if not being used"]
31802 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31803 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
31804 pub vel_z: [f32; 5],
31805 #[doc = "X-acceleration of waypoint, set to NaN if not being used"]
31806 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31807 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
31808 pub acc_x: [f32; 5],
31809 #[doc = "Y-acceleration of waypoint, set to NaN if not being used"]
31810 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31811 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
31812 pub acc_y: [f32; 5],
31813 #[doc = "Z-acceleration of waypoint, set to NaN if not being used"]
31814 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31815 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
31816 pub acc_z: [f32; 5],
31817 #[doc = "Yaw angle, set to NaN if not being used"]
31818 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31819 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
31820 pub pos_yaw: [f32; 5],
31821 #[doc = "Yaw rate, set to NaN if not being used"]
31822 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31823 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
31824 pub vel_yaw: [f32; 5],
31825 #[doc = "MAV_CMD command id of waypoint, set to UINT16_MAX if not being used."]
31826 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31827 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
31828 pub command: [u16; 5],
31829 #[doc = "Number of valid points (up-to 5 waypoints are possible)"]
31830 pub valid_points: u8,
31831}
31832impl TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA {
31833 pub const ENCODED_LEN: usize = 239usize;
31834 pub const DEFAULT: Self = Self {
31835 time_usec: 0_u64,
31836 pos_x: [0.0_f32; 5usize],
31837 pos_y: [0.0_f32; 5usize],
31838 pos_z: [0.0_f32; 5usize],
31839 vel_x: [0.0_f32; 5usize],
31840 vel_y: [0.0_f32; 5usize],
31841 vel_z: [0.0_f32; 5usize],
31842 acc_x: [0.0_f32; 5usize],
31843 acc_y: [0.0_f32; 5usize],
31844 acc_z: [0.0_f32; 5usize],
31845 pos_yaw: [0.0_f32; 5usize],
31846 vel_yaw: [0.0_f32; 5usize],
31847 command: [0_u16; 5usize],
31848 valid_points: 0_u8,
31849 };
31850 #[cfg(feature = "arbitrary")]
31851 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31852 use arbitrary::{Arbitrary, Unstructured};
31853 let mut buf = [0u8; 1024];
31854 rng.fill_bytes(&mut buf);
31855 let mut unstructured = Unstructured::new(&buf);
31856 Self::arbitrary(&mut unstructured).unwrap_or_default()
31857 }
31858}
31859impl Default for TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA {
31860 fn default() -> Self {
31861 Self::DEFAULT.clone()
31862 }
31863}
31864impl MessageData for TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA {
31865 type Message = MavMessage;
31866 const ID: u32 = 332u32;
31867 const NAME: &'static str = "TRAJECTORY_REPRESENTATION_WAYPOINTS";
31868 const EXTRA_CRC: u8 = 236u8;
31869 const ENCODED_LEN: usize = 239usize;
31870 fn deser(
31871 _version: MavlinkVersion,
31872 __input: &[u8],
31873 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31874 let avail_len = __input.len();
31875 let mut payload_buf = [0; Self::ENCODED_LEN];
31876 let mut buf = if avail_len < Self::ENCODED_LEN {
31877 payload_buf[0..avail_len].copy_from_slice(__input);
31878 Bytes::new(&payload_buf)
31879 } else {
31880 Bytes::new(__input)
31881 };
31882 let mut __struct = Self::default();
31883 __struct.time_usec = buf.get_u64_le()?;
31884 for v in &mut __struct.pos_x {
31885 let val = buf.get_f32_le()?;
31886 *v = val;
31887 }
31888 for v in &mut __struct.pos_y {
31889 let val = buf.get_f32_le()?;
31890 *v = val;
31891 }
31892 for v in &mut __struct.pos_z {
31893 let val = buf.get_f32_le()?;
31894 *v = val;
31895 }
31896 for v in &mut __struct.vel_x {
31897 let val = buf.get_f32_le()?;
31898 *v = val;
31899 }
31900 for v in &mut __struct.vel_y {
31901 let val = buf.get_f32_le()?;
31902 *v = val;
31903 }
31904 for v in &mut __struct.vel_z {
31905 let val = buf.get_f32_le()?;
31906 *v = val;
31907 }
31908 for v in &mut __struct.acc_x {
31909 let val = buf.get_f32_le()?;
31910 *v = val;
31911 }
31912 for v in &mut __struct.acc_y {
31913 let val = buf.get_f32_le()?;
31914 *v = val;
31915 }
31916 for v in &mut __struct.acc_z {
31917 let val = buf.get_f32_le()?;
31918 *v = val;
31919 }
31920 for v in &mut __struct.pos_yaw {
31921 let val = buf.get_f32_le()?;
31922 *v = val;
31923 }
31924 for v in &mut __struct.vel_yaw {
31925 let val = buf.get_f32_le()?;
31926 *v = val;
31927 }
31928 for v in &mut __struct.command {
31929 let val = buf.get_u16_le()?;
31930 *v = val;
31931 }
31932 __struct.valid_points = buf.get_u8()?;
31933 Ok(__struct)
31934 }
31935 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31936 let mut __tmp = BytesMut::new(bytes);
31937 #[allow(clippy::absurd_extreme_comparisons)]
31938 #[allow(unused_comparisons)]
31939 if __tmp.remaining() < Self::ENCODED_LEN {
31940 panic!(
31941 "buffer is too small (need {} bytes, but got {})",
31942 Self::ENCODED_LEN,
31943 __tmp.remaining(),
31944 )
31945 }
31946 __tmp.put_u64_le(self.time_usec);
31947 for val in &self.pos_x {
31948 __tmp.put_f32_le(*val);
31949 }
31950 for val in &self.pos_y {
31951 __tmp.put_f32_le(*val);
31952 }
31953 for val in &self.pos_z {
31954 __tmp.put_f32_le(*val);
31955 }
31956 for val in &self.vel_x {
31957 __tmp.put_f32_le(*val);
31958 }
31959 for val in &self.vel_y {
31960 __tmp.put_f32_le(*val);
31961 }
31962 for val in &self.vel_z {
31963 __tmp.put_f32_le(*val);
31964 }
31965 for val in &self.acc_x {
31966 __tmp.put_f32_le(*val);
31967 }
31968 for val in &self.acc_y {
31969 __tmp.put_f32_le(*val);
31970 }
31971 for val in &self.acc_z {
31972 __tmp.put_f32_le(*val);
31973 }
31974 for val in &self.pos_yaw {
31975 __tmp.put_f32_le(*val);
31976 }
31977 for val in &self.vel_yaw {
31978 __tmp.put_f32_le(*val);
31979 }
31980 for val in &self.command {
31981 __tmp.put_u16_le(*val);
31982 }
31983 __tmp.put_u8(self.valid_points);
31984 if matches!(version, MavlinkVersion::V2) {
31985 let len = __tmp.len();
31986 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31987 } else {
31988 __tmp.len()
31989 }
31990 }
31991}
31992#[doc = "Message for transporting \"arbitrary\" variable-length data from one component to another (broadcast is not forbidden, but discouraged). The encoding of the data is usually extension specific, i.e. determined by the source, and is usually not documented as part of the MAVLink specification."]
31993#[doc = ""]
31994#[doc = "ID: 385"]
31995#[derive(Debug, Clone, PartialEq)]
31996#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31997#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31998#[cfg_attr(feature = "ts", derive(TS))]
31999#[cfg_attr(feature = "ts", ts(export))]
32000pub struct TUNNEL_DATA {
32001 #[doc = "A code that identifies the content of the payload (0 for unknown, which is the default). If this code is less than 32768, it is a 'registered' payload type and the corresponding code should be added to the MAV_TUNNEL_PAYLOAD_TYPE enum. Software creators can register blocks of types as needed. Codes greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase."]
32002 pub payload_type: MavTunnelPayloadType,
32003 #[doc = "System ID (can be 0 for broadcast, but this is discouraged)"]
32004 pub target_system: u8,
32005 #[doc = "Component ID (can be 0 for broadcast, but this is discouraged)"]
32006 pub target_component: u8,
32007 #[doc = "Length of the data transported in payload"]
32008 pub payload_length: u8,
32009 #[doc = "Variable length payload. The payload length is defined by payload_length. The entire content of this block is opaque unless you understand the encoding specified by payload_type."]
32010 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
32011 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
32012 pub payload: [u8; 128],
32013}
32014impl TUNNEL_DATA {
32015 pub const ENCODED_LEN: usize = 133usize;
32016 pub const DEFAULT: Self = Self {
32017 payload_type: MavTunnelPayloadType::DEFAULT,
32018 target_system: 0_u8,
32019 target_component: 0_u8,
32020 payload_length: 0_u8,
32021 payload: [0_u8; 128usize],
32022 };
32023 #[cfg(feature = "arbitrary")]
32024 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
32025 use arbitrary::{Arbitrary, Unstructured};
32026 let mut buf = [0u8; 1024];
32027 rng.fill_bytes(&mut buf);
32028 let mut unstructured = Unstructured::new(&buf);
32029 Self::arbitrary(&mut unstructured).unwrap_or_default()
32030 }
32031}
32032impl Default for TUNNEL_DATA {
32033 fn default() -> Self {
32034 Self::DEFAULT.clone()
32035 }
32036}
32037impl MessageData for TUNNEL_DATA {
32038 type Message = MavMessage;
32039 const ID: u32 = 385u32;
32040 const NAME: &'static str = "TUNNEL";
32041 const EXTRA_CRC: u8 = 147u8;
32042 const ENCODED_LEN: usize = 133usize;
32043 fn deser(
32044 _version: MavlinkVersion,
32045 __input: &[u8],
32046 ) -> Result<Self, ::mavlink_core::error::ParserError> {
32047 let avail_len = __input.len();
32048 let mut payload_buf = [0; Self::ENCODED_LEN];
32049 let mut buf = if avail_len < Self::ENCODED_LEN {
32050 payload_buf[0..avail_len].copy_from_slice(__input);
32051 Bytes::new(&payload_buf)
32052 } else {
32053 Bytes::new(__input)
32054 };
32055 let mut __struct = Self::default();
32056 let tmp = buf.get_u16_le()?;
32057 __struct.payload_type = FromPrimitive::from_u16(tmp).ok_or(
32058 ::mavlink_core::error::ParserError::InvalidEnum {
32059 enum_type: "MavTunnelPayloadType",
32060 value: tmp as u64,
32061 },
32062 )?;
32063 __struct.target_system = buf.get_u8()?;
32064 __struct.target_component = buf.get_u8()?;
32065 __struct.payload_length = buf.get_u8()?;
32066 for v in &mut __struct.payload {
32067 let val = buf.get_u8()?;
32068 *v = val;
32069 }
32070 Ok(__struct)
32071 }
32072 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
32073 let mut __tmp = BytesMut::new(bytes);
32074 #[allow(clippy::absurd_extreme_comparisons)]
32075 #[allow(unused_comparisons)]
32076 if __tmp.remaining() < Self::ENCODED_LEN {
32077 panic!(
32078 "buffer is too small (need {} bytes, but got {})",
32079 Self::ENCODED_LEN,
32080 __tmp.remaining(),
32081 )
32082 }
32083 __tmp.put_u16_le(self.payload_type as u16);
32084 __tmp.put_u8(self.target_system);
32085 __tmp.put_u8(self.target_component);
32086 __tmp.put_u8(self.payload_length);
32087 for val in &self.payload {
32088 __tmp.put_u8(*val);
32089 }
32090 if matches!(version, MavlinkVersion::V2) {
32091 let len = __tmp.len();
32092 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
32093 } else {
32094 __tmp.len()
32095 }
32096 }
32097}
32098#[doc = "General information describing a particular UAVCAN node. Please refer to the definition of the UAVCAN service \"uavcan.protocol.GetNodeInfo\" for the background information. This message should be emitted by the system whenever a new node appears online, or an existing node reboots. Additionally, it can be emitted upon request from the other end of the MAVLink channel (see MAV_CMD_UAVCAN_GET_NODE_INFO). It is also not prohibited to emit this message unconditionally at a low frequency. The UAVCAN specification is available at <http://uavcan.org>."]
32099#[doc = ""]
32100#[doc = "ID: 311"]
32101#[derive(Debug, Clone, PartialEq)]
32102#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
32103#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
32104#[cfg_attr(feature = "ts", derive(TS))]
32105#[cfg_attr(feature = "ts", ts(export))]
32106pub struct UAVCAN_NODE_INFO_DATA {
32107 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
32108 pub time_usec: u64,
32109 #[doc = "Time since the start-up of the node."]
32110 pub uptime_sec: u32,
32111 #[doc = "Version control system (VCS) revision identifier (e.g. git short commit hash). 0 if unknown."]
32112 pub sw_vcs_commit: u32,
32113 #[doc = "Node name string. For example, \"sapog.px4.io\"."]
32114 #[cfg_attr(feature = "ts", ts(type = "string"))]
32115 pub name: CharArray<80>,
32116 #[doc = "Hardware major version number."]
32117 pub hw_version_major: u8,
32118 #[doc = "Hardware minor version number."]
32119 pub hw_version_minor: u8,
32120 #[doc = "Hardware unique 128-bit ID."]
32121 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
32122 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
32123 pub hw_unique_id: [u8; 16],
32124 #[doc = "Software major version number."]
32125 pub sw_version_major: u8,
32126 #[doc = "Software minor version number."]
32127 pub sw_version_minor: u8,
32128}
32129impl UAVCAN_NODE_INFO_DATA {
32130 pub const ENCODED_LEN: usize = 116usize;
32131 pub const DEFAULT: Self = Self {
32132 time_usec: 0_u64,
32133 uptime_sec: 0_u32,
32134 sw_vcs_commit: 0_u32,
32135 name: CharArray::new([0_u8; 80usize]),
32136 hw_version_major: 0_u8,
32137 hw_version_minor: 0_u8,
32138 hw_unique_id: [0_u8; 16usize],
32139 sw_version_major: 0_u8,
32140 sw_version_minor: 0_u8,
32141 };
32142 #[cfg(feature = "arbitrary")]
32143 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
32144 use arbitrary::{Arbitrary, Unstructured};
32145 let mut buf = [0u8; 1024];
32146 rng.fill_bytes(&mut buf);
32147 let mut unstructured = Unstructured::new(&buf);
32148 Self::arbitrary(&mut unstructured).unwrap_or_default()
32149 }
32150}
32151impl Default for UAVCAN_NODE_INFO_DATA {
32152 fn default() -> Self {
32153 Self::DEFAULT.clone()
32154 }
32155}
32156impl MessageData for UAVCAN_NODE_INFO_DATA {
32157 type Message = MavMessage;
32158 const ID: u32 = 311u32;
32159 const NAME: &'static str = "UAVCAN_NODE_INFO";
32160 const EXTRA_CRC: u8 = 95u8;
32161 const ENCODED_LEN: usize = 116usize;
32162 fn deser(
32163 _version: MavlinkVersion,
32164 __input: &[u8],
32165 ) -> Result<Self, ::mavlink_core::error::ParserError> {
32166 let avail_len = __input.len();
32167 let mut payload_buf = [0; Self::ENCODED_LEN];
32168 let mut buf = if avail_len < Self::ENCODED_LEN {
32169 payload_buf[0..avail_len].copy_from_slice(__input);
32170 Bytes::new(&payload_buf)
32171 } else {
32172 Bytes::new(__input)
32173 };
32174 let mut __struct = Self::default();
32175 __struct.time_usec = buf.get_u64_le()?;
32176 __struct.uptime_sec = buf.get_u32_le()?;
32177 __struct.sw_vcs_commit = buf.get_u32_le()?;
32178 let mut tmp = [0_u8; 80usize];
32179 for v in &mut tmp {
32180 *v = buf.get_u8()?;
32181 }
32182 __struct.name = CharArray::new(tmp);
32183 __struct.hw_version_major = buf.get_u8()?;
32184 __struct.hw_version_minor = buf.get_u8()?;
32185 for v in &mut __struct.hw_unique_id {
32186 let val = buf.get_u8()?;
32187 *v = val;
32188 }
32189 __struct.sw_version_major = buf.get_u8()?;
32190 __struct.sw_version_minor = buf.get_u8()?;
32191 Ok(__struct)
32192 }
32193 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
32194 let mut __tmp = BytesMut::new(bytes);
32195 #[allow(clippy::absurd_extreme_comparisons)]
32196 #[allow(unused_comparisons)]
32197 if __tmp.remaining() < Self::ENCODED_LEN {
32198 panic!(
32199 "buffer is too small (need {} bytes, but got {})",
32200 Self::ENCODED_LEN,
32201 __tmp.remaining(),
32202 )
32203 }
32204 __tmp.put_u64_le(self.time_usec);
32205 __tmp.put_u32_le(self.uptime_sec);
32206 __tmp.put_u32_le(self.sw_vcs_commit);
32207 for val in &self.name {
32208 __tmp.put_u8(*val);
32209 }
32210 __tmp.put_u8(self.hw_version_major);
32211 __tmp.put_u8(self.hw_version_minor);
32212 for val in &self.hw_unique_id {
32213 __tmp.put_u8(*val);
32214 }
32215 __tmp.put_u8(self.sw_version_major);
32216 __tmp.put_u8(self.sw_version_minor);
32217 if matches!(version, MavlinkVersion::V2) {
32218 let len = __tmp.len();
32219 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
32220 } else {
32221 __tmp.len()
32222 }
32223 }
32224}
32225#[doc = "General status information of an UAVCAN node. Please refer to the definition of the UAVCAN message \"uavcan.protocol.NodeStatus\" for the background information. The UAVCAN specification is available at <http://uavcan.org>."]
32226#[doc = ""]
32227#[doc = "ID: 310"]
32228#[derive(Debug, Clone, PartialEq)]
32229#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
32230#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
32231#[cfg_attr(feature = "ts", derive(TS))]
32232#[cfg_attr(feature = "ts", ts(export))]
32233pub struct UAVCAN_NODE_STATUS_DATA {
32234 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
32235 pub time_usec: u64,
32236 #[doc = "Time since the start-up of the node."]
32237 pub uptime_sec: u32,
32238 #[doc = "Vendor-specific status information."]
32239 pub vendor_specific_status_code: u16,
32240 #[doc = "Generalized node health status."]
32241 pub health: UavcanNodeHealth,
32242 #[doc = "Generalized operating mode."]
32243 pub mode: UavcanNodeMode,
32244 #[doc = "Not used currently."]
32245 pub sub_mode: u8,
32246}
32247impl UAVCAN_NODE_STATUS_DATA {
32248 pub const ENCODED_LEN: usize = 17usize;
32249 pub const DEFAULT: Self = Self {
32250 time_usec: 0_u64,
32251 uptime_sec: 0_u32,
32252 vendor_specific_status_code: 0_u16,
32253 health: UavcanNodeHealth::DEFAULT,
32254 mode: UavcanNodeMode::DEFAULT,
32255 sub_mode: 0_u8,
32256 };
32257 #[cfg(feature = "arbitrary")]
32258 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
32259 use arbitrary::{Arbitrary, Unstructured};
32260 let mut buf = [0u8; 1024];
32261 rng.fill_bytes(&mut buf);
32262 let mut unstructured = Unstructured::new(&buf);
32263 Self::arbitrary(&mut unstructured).unwrap_or_default()
32264 }
32265}
32266impl Default for UAVCAN_NODE_STATUS_DATA {
32267 fn default() -> Self {
32268 Self::DEFAULT.clone()
32269 }
32270}
32271impl MessageData for UAVCAN_NODE_STATUS_DATA {
32272 type Message = MavMessage;
32273 const ID: u32 = 310u32;
32274 const NAME: &'static str = "UAVCAN_NODE_STATUS";
32275 const EXTRA_CRC: u8 = 28u8;
32276 const ENCODED_LEN: usize = 17usize;
32277 fn deser(
32278 _version: MavlinkVersion,
32279 __input: &[u8],
32280 ) -> Result<Self, ::mavlink_core::error::ParserError> {
32281 let avail_len = __input.len();
32282 let mut payload_buf = [0; Self::ENCODED_LEN];
32283 let mut buf = if avail_len < Self::ENCODED_LEN {
32284 payload_buf[0..avail_len].copy_from_slice(__input);
32285 Bytes::new(&payload_buf)
32286 } else {
32287 Bytes::new(__input)
32288 };
32289 let mut __struct = Self::default();
32290 __struct.time_usec = buf.get_u64_le()?;
32291 __struct.uptime_sec = buf.get_u32_le()?;
32292 __struct.vendor_specific_status_code = buf.get_u16_le()?;
32293 let tmp = buf.get_u8()?;
32294 __struct.health =
32295 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
32296 enum_type: "UavcanNodeHealth",
32297 value: tmp as u64,
32298 })?;
32299 let tmp = buf.get_u8()?;
32300 __struct.mode =
32301 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
32302 enum_type: "UavcanNodeMode",
32303 value: tmp as u64,
32304 })?;
32305 __struct.sub_mode = buf.get_u8()?;
32306 Ok(__struct)
32307 }
32308 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
32309 let mut __tmp = BytesMut::new(bytes);
32310 #[allow(clippy::absurd_extreme_comparisons)]
32311 #[allow(unused_comparisons)]
32312 if __tmp.remaining() < Self::ENCODED_LEN {
32313 panic!(
32314 "buffer is too small (need {} bytes, but got {})",
32315 Self::ENCODED_LEN,
32316 __tmp.remaining(),
32317 )
32318 }
32319 __tmp.put_u64_le(self.time_usec);
32320 __tmp.put_u32_le(self.uptime_sec);
32321 __tmp.put_u16_le(self.vendor_specific_status_code);
32322 __tmp.put_u8(self.health as u8);
32323 __tmp.put_u8(self.mode as u8);
32324 __tmp.put_u8(self.sub_mode);
32325 if matches!(version, MavlinkVersion::V2) {
32326 let len = __tmp.len();
32327 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
32328 } else {
32329 __tmp.len()
32330 }
32331 }
32332}
32333#[doc = "The global position resulting from GPS and sensor fusion."]
32334#[doc = ""]
32335#[doc = "ID: 340"]
32336#[derive(Debug, Clone, PartialEq)]
32337#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
32338#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
32339#[cfg_attr(feature = "ts", derive(TS))]
32340#[cfg_attr(feature = "ts", ts(export))]
32341pub struct UTM_GLOBAL_POSITION_DATA {
32342 #[doc = "Time of applicability of position (microseconds since UNIX epoch)."]
32343 pub time: u64,
32344 #[doc = "Latitude (WGS84)"]
32345 pub lat: i32,
32346 #[doc = "Longitude (WGS84)"]
32347 pub lon: i32,
32348 #[doc = "Altitude (WGS84)"]
32349 pub alt: i32,
32350 #[doc = "Altitude above ground"]
32351 pub relative_alt: i32,
32352 #[doc = "Next waypoint, latitude (WGS84)"]
32353 pub next_lat: i32,
32354 #[doc = "Next waypoint, longitude (WGS84)"]
32355 pub next_lon: i32,
32356 #[doc = "Next waypoint, altitude (WGS84)"]
32357 pub next_alt: i32,
32358 #[doc = "Ground X speed (latitude, positive north)"]
32359 pub vx: i16,
32360 #[doc = "Ground Y speed (longitude, positive east)"]
32361 pub vy: i16,
32362 #[doc = "Ground Z speed (altitude, positive down)"]
32363 pub vz: i16,
32364 #[doc = "Horizontal position uncertainty (standard deviation)"]
32365 pub h_acc: u16,
32366 #[doc = "Altitude uncertainty (standard deviation)"]
32367 pub v_acc: u16,
32368 #[doc = "Speed uncertainty (standard deviation)"]
32369 pub vel_acc: u16,
32370 #[doc = "Time until next update. Set to 0 if unknown or in data driven mode."]
32371 pub update_rate: u16,
32372 #[doc = "Unique UAS ID."]
32373 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
32374 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
32375 pub uas_id: [u8; 18],
32376 #[doc = "Flight state"]
32377 pub flight_state: UtmFlightState,
32378 #[doc = "Bitwise OR combination of the data available flags."]
32379 pub flags: UtmDataAvailFlags,
32380}
32381impl UTM_GLOBAL_POSITION_DATA {
32382 pub const ENCODED_LEN: usize = 70usize;
32383 pub const DEFAULT: Self = Self {
32384 time: 0_u64,
32385 lat: 0_i32,
32386 lon: 0_i32,
32387 alt: 0_i32,
32388 relative_alt: 0_i32,
32389 next_lat: 0_i32,
32390 next_lon: 0_i32,
32391 next_alt: 0_i32,
32392 vx: 0_i16,
32393 vy: 0_i16,
32394 vz: 0_i16,
32395 h_acc: 0_u16,
32396 v_acc: 0_u16,
32397 vel_acc: 0_u16,
32398 update_rate: 0_u16,
32399 uas_id: [0_u8; 18usize],
32400 flight_state: UtmFlightState::DEFAULT,
32401 flags: UtmDataAvailFlags::DEFAULT,
32402 };
32403 #[cfg(feature = "arbitrary")]
32404 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
32405 use arbitrary::{Arbitrary, Unstructured};
32406 let mut buf = [0u8; 1024];
32407 rng.fill_bytes(&mut buf);
32408 let mut unstructured = Unstructured::new(&buf);
32409 Self::arbitrary(&mut unstructured).unwrap_or_default()
32410 }
32411}
32412impl Default for UTM_GLOBAL_POSITION_DATA {
32413 fn default() -> Self {
32414 Self::DEFAULT.clone()
32415 }
32416}
32417impl MessageData for UTM_GLOBAL_POSITION_DATA {
32418 type Message = MavMessage;
32419 const ID: u32 = 340u32;
32420 const NAME: &'static str = "UTM_GLOBAL_POSITION";
32421 const EXTRA_CRC: u8 = 99u8;
32422 const ENCODED_LEN: usize = 70usize;
32423 fn deser(
32424 _version: MavlinkVersion,
32425 __input: &[u8],
32426 ) -> Result<Self, ::mavlink_core::error::ParserError> {
32427 let avail_len = __input.len();
32428 let mut payload_buf = [0; Self::ENCODED_LEN];
32429 let mut buf = if avail_len < Self::ENCODED_LEN {
32430 payload_buf[0..avail_len].copy_from_slice(__input);
32431 Bytes::new(&payload_buf)
32432 } else {
32433 Bytes::new(__input)
32434 };
32435 let mut __struct = Self::default();
32436 __struct.time = buf.get_u64_le()?;
32437 __struct.lat = buf.get_i32_le()?;
32438 __struct.lon = buf.get_i32_le()?;
32439 __struct.alt = buf.get_i32_le()?;
32440 __struct.relative_alt = buf.get_i32_le()?;
32441 __struct.next_lat = buf.get_i32_le()?;
32442 __struct.next_lon = buf.get_i32_le()?;
32443 __struct.next_alt = buf.get_i32_le()?;
32444 __struct.vx = buf.get_i16_le()?;
32445 __struct.vy = buf.get_i16_le()?;
32446 __struct.vz = buf.get_i16_le()?;
32447 __struct.h_acc = buf.get_u16_le()?;
32448 __struct.v_acc = buf.get_u16_le()?;
32449 __struct.vel_acc = buf.get_u16_le()?;
32450 __struct.update_rate = buf.get_u16_le()?;
32451 for v in &mut __struct.uas_id {
32452 let val = buf.get_u8()?;
32453 *v = val;
32454 }
32455 let tmp = buf.get_u8()?;
32456 __struct.flight_state =
32457 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
32458 enum_type: "UtmFlightState",
32459 value: tmp as u64,
32460 })?;
32461 let tmp = buf.get_u8()?;
32462 __struct.flags = UtmDataAvailFlags::from_bits(tmp as <UtmDataAvailFlags as Flags>::Bits)
32463 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
32464 flag_type: "UtmDataAvailFlags",
32465 value: tmp as u64,
32466 })?;
32467 Ok(__struct)
32468 }
32469 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
32470 let mut __tmp = BytesMut::new(bytes);
32471 #[allow(clippy::absurd_extreme_comparisons)]
32472 #[allow(unused_comparisons)]
32473 if __tmp.remaining() < Self::ENCODED_LEN {
32474 panic!(
32475 "buffer is too small (need {} bytes, but got {})",
32476 Self::ENCODED_LEN,
32477 __tmp.remaining(),
32478 )
32479 }
32480 __tmp.put_u64_le(self.time);
32481 __tmp.put_i32_le(self.lat);
32482 __tmp.put_i32_le(self.lon);
32483 __tmp.put_i32_le(self.alt);
32484 __tmp.put_i32_le(self.relative_alt);
32485 __tmp.put_i32_le(self.next_lat);
32486 __tmp.put_i32_le(self.next_lon);
32487 __tmp.put_i32_le(self.next_alt);
32488 __tmp.put_i16_le(self.vx);
32489 __tmp.put_i16_le(self.vy);
32490 __tmp.put_i16_le(self.vz);
32491 __tmp.put_u16_le(self.h_acc);
32492 __tmp.put_u16_le(self.v_acc);
32493 __tmp.put_u16_le(self.vel_acc);
32494 __tmp.put_u16_le(self.update_rate);
32495 for val in &self.uas_id {
32496 __tmp.put_u8(*val);
32497 }
32498 __tmp.put_u8(self.flight_state as u8);
32499 __tmp.put_u8(self.flags.bits() as u8);
32500 if matches!(version, MavlinkVersion::V2) {
32501 let len = __tmp.len();
32502 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
32503 } else {
32504 __tmp.len()
32505 }
32506 }
32507}
32508#[doc = "Message implementing parts of the V2 payload specs in V1 frames for transitional support."]
32509#[doc = ""]
32510#[doc = "ID: 248"]
32511#[derive(Debug, Clone, PartialEq)]
32512#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
32513#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
32514#[cfg_attr(feature = "ts", derive(TS))]
32515#[cfg_attr(feature = "ts", ts(export))]
32516pub struct V2_EXTENSION_DATA {
32517 #[doc = "A code that identifies the software component that understands this message (analogous to USB device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to <https://github.com/mavlink/mavlink/definition_files/extension_message_ids.xml>. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase."]
32518 pub message_type: u16,
32519 #[doc = "Network ID (0 for broadcast)"]
32520 pub target_network: u8,
32521 #[doc = "System ID (0 for broadcast)"]
32522 pub target_system: u8,
32523 #[doc = "Component ID (0 for broadcast)"]
32524 pub target_component: u8,
32525 #[doc = "Variable length payload. The length must be encoded in the payload as part of the message_type protocol, e.g. by including the length as payload data, or by terminating the payload data with a non-zero marker. This is required in order to reconstruct zero-terminated payloads that are (or otherwise would be) trimmed by MAVLink 2 empty-byte truncation. The entire content of the payload block is opaque unless you understand the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the MAVLink specification."]
32526 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
32527 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
32528 pub payload: [u8; 249],
32529}
32530impl V2_EXTENSION_DATA {
32531 pub const ENCODED_LEN: usize = 254usize;
32532 pub const DEFAULT: Self = Self {
32533 message_type: 0_u16,
32534 target_network: 0_u8,
32535 target_system: 0_u8,
32536 target_component: 0_u8,
32537 payload: [0_u8; 249usize],
32538 };
32539 #[cfg(feature = "arbitrary")]
32540 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
32541 use arbitrary::{Arbitrary, Unstructured};
32542 let mut buf = [0u8; 1024];
32543 rng.fill_bytes(&mut buf);
32544 let mut unstructured = Unstructured::new(&buf);
32545 Self::arbitrary(&mut unstructured).unwrap_or_default()
32546 }
32547}
32548impl Default for V2_EXTENSION_DATA {
32549 fn default() -> Self {
32550 Self::DEFAULT.clone()
32551 }
32552}
32553impl MessageData for V2_EXTENSION_DATA {
32554 type Message = MavMessage;
32555 const ID: u32 = 248u32;
32556 const NAME: &'static str = "V2_EXTENSION";
32557 const EXTRA_CRC: u8 = 8u8;
32558 const ENCODED_LEN: usize = 254usize;
32559 fn deser(
32560 _version: MavlinkVersion,
32561 __input: &[u8],
32562 ) -> Result<Self, ::mavlink_core::error::ParserError> {
32563 let avail_len = __input.len();
32564 let mut payload_buf = [0; Self::ENCODED_LEN];
32565 let mut buf = if avail_len < Self::ENCODED_LEN {
32566 payload_buf[0..avail_len].copy_from_slice(__input);
32567 Bytes::new(&payload_buf)
32568 } else {
32569 Bytes::new(__input)
32570 };
32571 let mut __struct = Self::default();
32572 __struct.message_type = buf.get_u16_le()?;
32573 __struct.target_network = buf.get_u8()?;
32574 __struct.target_system = buf.get_u8()?;
32575 __struct.target_component = buf.get_u8()?;
32576 for v in &mut __struct.payload {
32577 let val = buf.get_u8()?;
32578 *v = val;
32579 }
32580 Ok(__struct)
32581 }
32582 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
32583 let mut __tmp = BytesMut::new(bytes);
32584 #[allow(clippy::absurd_extreme_comparisons)]
32585 #[allow(unused_comparisons)]
32586 if __tmp.remaining() < Self::ENCODED_LEN {
32587 panic!(
32588 "buffer is too small (need {} bytes, but got {})",
32589 Self::ENCODED_LEN,
32590 __tmp.remaining(),
32591 )
32592 }
32593 __tmp.put_u16_le(self.message_type);
32594 __tmp.put_u8(self.target_network);
32595 __tmp.put_u8(self.target_system);
32596 __tmp.put_u8(self.target_component);
32597 for val in &self.payload {
32598 __tmp.put_u8(*val);
32599 }
32600 if matches!(version, MavlinkVersion::V2) {
32601 let len = __tmp.len();
32602 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
32603 } else {
32604 __tmp.len()
32605 }
32606 }
32607}
32608#[doc = "Metrics typically displayed on a HUD for fixed wing aircraft."]
32609#[doc = ""]
32610#[doc = "ID: 74"]
32611#[derive(Debug, Clone, PartialEq)]
32612#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
32613#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
32614#[cfg_attr(feature = "ts", derive(TS))]
32615#[cfg_attr(feature = "ts", ts(export))]
32616pub struct VFR_HUD_DATA {
32617 #[doc = "Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed."]
32618 pub airspeed: f32,
32619 #[doc = "Current ground speed."]
32620 pub groundspeed: f32,
32621 #[doc = "Current altitude (MSL)."]
32622 pub alt: f32,
32623 #[doc = "Current climb rate."]
32624 pub climb: f32,
32625 #[doc = "Current heading in compass units (0-360, 0=north)."]
32626 pub heading: i16,
32627 #[doc = "Current throttle setting (0 to 100)."]
32628 pub throttle: u16,
32629}
32630impl VFR_HUD_DATA {
32631 pub const ENCODED_LEN: usize = 20usize;
32632 pub const DEFAULT: Self = Self {
32633 airspeed: 0.0_f32,
32634 groundspeed: 0.0_f32,
32635 alt: 0.0_f32,
32636 climb: 0.0_f32,
32637 heading: 0_i16,
32638 throttle: 0_u16,
32639 };
32640 #[cfg(feature = "arbitrary")]
32641 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
32642 use arbitrary::{Arbitrary, Unstructured};
32643 let mut buf = [0u8; 1024];
32644 rng.fill_bytes(&mut buf);
32645 let mut unstructured = Unstructured::new(&buf);
32646 Self::arbitrary(&mut unstructured).unwrap_or_default()
32647 }
32648}
32649impl Default for VFR_HUD_DATA {
32650 fn default() -> Self {
32651 Self::DEFAULT.clone()
32652 }
32653}
32654impl MessageData for VFR_HUD_DATA {
32655 type Message = MavMessage;
32656 const ID: u32 = 74u32;
32657 const NAME: &'static str = "VFR_HUD";
32658 const EXTRA_CRC: u8 = 20u8;
32659 const ENCODED_LEN: usize = 20usize;
32660 fn deser(
32661 _version: MavlinkVersion,
32662 __input: &[u8],
32663 ) -> Result<Self, ::mavlink_core::error::ParserError> {
32664 let avail_len = __input.len();
32665 let mut payload_buf = [0; Self::ENCODED_LEN];
32666 let mut buf = if avail_len < Self::ENCODED_LEN {
32667 payload_buf[0..avail_len].copy_from_slice(__input);
32668 Bytes::new(&payload_buf)
32669 } else {
32670 Bytes::new(__input)
32671 };
32672 let mut __struct = Self::default();
32673 __struct.airspeed = buf.get_f32_le()?;
32674 __struct.groundspeed = buf.get_f32_le()?;
32675 __struct.alt = buf.get_f32_le()?;
32676 __struct.climb = buf.get_f32_le()?;
32677 __struct.heading = buf.get_i16_le()?;
32678 __struct.throttle = buf.get_u16_le()?;
32679 Ok(__struct)
32680 }
32681 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
32682 let mut __tmp = BytesMut::new(bytes);
32683 #[allow(clippy::absurd_extreme_comparisons)]
32684 #[allow(unused_comparisons)]
32685 if __tmp.remaining() < Self::ENCODED_LEN {
32686 panic!(
32687 "buffer is too small (need {} bytes, but got {})",
32688 Self::ENCODED_LEN,
32689 __tmp.remaining(),
32690 )
32691 }
32692 __tmp.put_f32_le(self.airspeed);
32693 __tmp.put_f32_le(self.groundspeed);
32694 __tmp.put_f32_le(self.alt);
32695 __tmp.put_f32_le(self.climb);
32696 __tmp.put_i16_le(self.heading);
32697 __tmp.put_u16_le(self.throttle);
32698 if matches!(version, MavlinkVersion::V2) {
32699 let len = __tmp.len();
32700 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
32701 } else {
32702 __tmp.len()
32703 }
32704 }
32705}
32706#[doc = "Vibration levels and accelerometer clipping."]
32707#[doc = ""]
32708#[doc = "ID: 241"]
32709#[derive(Debug, Clone, PartialEq)]
32710#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
32711#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
32712#[cfg_attr(feature = "ts", derive(TS))]
32713#[cfg_attr(feature = "ts", ts(export))]
32714pub struct VIBRATION_DATA {
32715 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
32716 pub time_usec: u64,
32717 #[doc = "Vibration levels on X-axis"]
32718 pub vibration_x: f32,
32719 #[doc = "Vibration levels on Y-axis"]
32720 pub vibration_y: f32,
32721 #[doc = "Vibration levels on Z-axis"]
32722 pub vibration_z: f32,
32723 #[doc = "first accelerometer clipping count"]
32724 pub clipping_0: u32,
32725 #[doc = "second accelerometer clipping count"]
32726 pub clipping_1: u32,
32727 #[doc = "third accelerometer clipping count"]
32728 pub clipping_2: u32,
32729}
32730impl VIBRATION_DATA {
32731 pub const ENCODED_LEN: usize = 32usize;
32732 pub const DEFAULT: Self = Self {
32733 time_usec: 0_u64,
32734 vibration_x: 0.0_f32,
32735 vibration_y: 0.0_f32,
32736 vibration_z: 0.0_f32,
32737 clipping_0: 0_u32,
32738 clipping_1: 0_u32,
32739 clipping_2: 0_u32,
32740 };
32741 #[cfg(feature = "arbitrary")]
32742 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
32743 use arbitrary::{Arbitrary, Unstructured};
32744 let mut buf = [0u8; 1024];
32745 rng.fill_bytes(&mut buf);
32746 let mut unstructured = Unstructured::new(&buf);
32747 Self::arbitrary(&mut unstructured).unwrap_or_default()
32748 }
32749}
32750impl Default for VIBRATION_DATA {
32751 fn default() -> Self {
32752 Self::DEFAULT.clone()
32753 }
32754}
32755impl MessageData for VIBRATION_DATA {
32756 type Message = MavMessage;
32757 const ID: u32 = 241u32;
32758 const NAME: &'static str = "VIBRATION";
32759 const EXTRA_CRC: u8 = 90u8;
32760 const ENCODED_LEN: usize = 32usize;
32761 fn deser(
32762 _version: MavlinkVersion,
32763 __input: &[u8],
32764 ) -> Result<Self, ::mavlink_core::error::ParserError> {
32765 let avail_len = __input.len();
32766 let mut payload_buf = [0; Self::ENCODED_LEN];
32767 let mut buf = if avail_len < Self::ENCODED_LEN {
32768 payload_buf[0..avail_len].copy_from_slice(__input);
32769 Bytes::new(&payload_buf)
32770 } else {
32771 Bytes::new(__input)
32772 };
32773 let mut __struct = Self::default();
32774 __struct.time_usec = buf.get_u64_le()?;
32775 __struct.vibration_x = buf.get_f32_le()?;
32776 __struct.vibration_y = buf.get_f32_le()?;
32777 __struct.vibration_z = buf.get_f32_le()?;
32778 __struct.clipping_0 = buf.get_u32_le()?;
32779 __struct.clipping_1 = buf.get_u32_le()?;
32780 __struct.clipping_2 = buf.get_u32_le()?;
32781 Ok(__struct)
32782 }
32783 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
32784 let mut __tmp = BytesMut::new(bytes);
32785 #[allow(clippy::absurd_extreme_comparisons)]
32786 #[allow(unused_comparisons)]
32787 if __tmp.remaining() < Self::ENCODED_LEN {
32788 panic!(
32789 "buffer is too small (need {} bytes, but got {})",
32790 Self::ENCODED_LEN,
32791 __tmp.remaining(),
32792 )
32793 }
32794 __tmp.put_u64_le(self.time_usec);
32795 __tmp.put_f32_le(self.vibration_x);
32796 __tmp.put_f32_le(self.vibration_y);
32797 __tmp.put_f32_le(self.vibration_z);
32798 __tmp.put_u32_le(self.clipping_0);
32799 __tmp.put_u32_le(self.clipping_1);
32800 __tmp.put_u32_le(self.clipping_2);
32801 if matches!(version, MavlinkVersion::V2) {
32802 let len = __tmp.len();
32803 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
32804 } else {
32805 __tmp.len()
32806 }
32807 }
32808}
32809#[doc = "Global position estimate from a Vicon motion system source."]
32810#[doc = ""]
32811#[doc = "ID: 104"]
32812#[derive(Debug, Clone, PartialEq)]
32813#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
32814#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
32815#[cfg_attr(feature = "ts", derive(TS))]
32816#[cfg_attr(feature = "ts", ts(export))]
32817pub struct VICON_POSITION_ESTIMATE_DATA {
32818 #[doc = "Timestamp (UNIX time or time since system boot)"]
32819 pub usec: u64,
32820 #[doc = "Global X position"]
32821 pub x: f32,
32822 #[doc = "Global Y position"]
32823 pub y: f32,
32824 #[doc = "Global Z position"]
32825 pub z: f32,
32826 #[doc = "Roll angle"]
32827 pub roll: f32,
32828 #[doc = "Pitch angle"]
32829 pub pitch: f32,
32830 #[doc = "Yaw angle"]
32831 pub yaw: f32,
32832 #[doc = "Row-major representation of 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
32833 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
32834 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
32835 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
32836 pub covariance: [f32; 21],
32837}
32838impl VICON_POSITION_ESTIMATE_DATA {
32839 pub const ENCODED_LEN: usize = 116usize;
32840 pub const DEFAULT: Self = Self {
32841 usec: 0_u64,
32842 x: 0.0_f32,
32843 y: 0.0_f32,
32844 z: 0.0_f32,
32845 roll: 0.0_f32,
32846 pitch: 0.0_f32,
32847 yaw: 0.0_f32,
32848 covariance: [0.0_f32; 21usize],
32849 };
32850 #[cfg(feature = "arbitrary")]
32851 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
32852 use arbitrary::{Arbitrary, Unstructured};
32853 let mut buf = [0u8; 1024];
32854 rng.fill_bytes(&mut buf);
32855 let mut unstructured = Unstructured::new(&buf);
32856 Self::arbitrary(&mut unstructured).unwrap_or_default()
32857 }
32858}
32859impl Default for VICON_POSITION_ESTIMATE_DATA {
32860 fn default() -> Self {
32861 Self::DEFAULT.clone()
32862 }
32863}
32864impl MessageData for VICON_POSITION_ESTIMATE_DATA {
32865 type Message = MavMessage;
32866 const ID: u32 = 104u32;
32867 const NAME: &'static str = "VICON_POSITION_ESTIMATE";
32868 const EXTRA_CRC: u8 = 56u8;
32869 const ENCODED_LEN: usize = 116usize;
32870 fn deser(
32871 _version: MavlinkVersion,
32872 __input: &[u8],
32873 ) -> Result<Self, ::mavlink_core::error::ParserError> {
32874 let avail_len = __input.len();
32875 let mut payload_buf = [0; Self::ENCODED_LEN];
32876 let mut buf = if avail_len < Self::ENCODED_LEN {
32877 payload_buf[0..avail_len].copy_from_slice(__input);
32878 Bytes::new(&payload_buf)
32879 } else {
32880 Bytes::new(__input)
32881 };
32882 let mut __struct = Self::default();
32883 __struct.usec = buf.get_u64_le()?;
32884 __struct.x = buf.get_f32_le()?;
32885 __struct.y = buf.get_f32_le()?;
32886 __struct.z = buf.get_f32_le()?;
32887 __struct.roll = buf.get_f32_le()?;
32888 __struct.pitch = buf.get_f32_le()?;
32889 __struct.yaw = buf.get_f32_le()?;
32890 for v in &mut __struct.covariance {
32891 let val = buf.get_f32_le()?;
32892 *v = val;
32893 }
32894 Ok(__struct)
32895 }
32896 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
32897 let mut __tmp = BytesMut::new(bytes);
32898 #[allow(clippy::absurd_extreme_comparisons)]
32899 #[allow(unused_comparisons)]
32900 if __tmp.remaining() < Self::ENCODED_LEN {
32901 panic!(
32902 "buffer is too small (need {} bytes, but got {})",
32903 Self::ENCODED_LEN,
32904 __tmp.remaining(),
32905 )
32906 }
32907 __tmp.put_u64_le(self.usec);
32908 __tmp.put_f32_le(self.x);
32909 __tmp.put_f32_le(self.y);
32910 __tmp.put_f32_le(self.z);
32911 __tmp.put_f32_le(self.roll);
32912 __tmp.put_f32_le(self.pitch);
32913 __tmp.put_f32_le(self.yaw);
32914 if matches!(version, MavlinkVersion::V2) {
32915 for val in &self.covariance {
32916 __tmp.put_f32_le(*val);
32917 }
32918 let len = __tmp.len();
32919 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
32920 } else {
32921 __tmp.len()
32922 }
32923 }
32924}
32925#[doc = "Information about video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE, where param2 indicates the video stream id: 0 for all streams, 1 for first, 2 for second, etc."]
32926#[doc = ""]
32927#[doc = "ID: 269"]
32928#[derive(Debug, Clone, PartialEq)]
32929#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
32930#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
32931#[cfg_attr(feature = "ts", derive(TS))]
32932#[cfg_attr(feature = "ts", ts(export))]
32933pub struct VIDEO_STREAM_INFORMATION_DATA {
32934 #[doc = "Frame rate."]
32935 pub framerate: f32,
32936 #[doc = "Bit rate."]
32937 pub bitrate: u32,
32938 #[doc = "Bitmap of stream status flags."]
32939 pub flags: VideoStreamStatusFlags,
32940 #[doc = "Horizontal resolution."]
32941 pub resolution_h: u16,
32942 #[doc = "Vertical resolution."]
32943 pub resolution_v: u16,
32944 #[doc = "Video image rotation clockwise."]
32945 pub rotation: u16,
32946 #[doc = "Horizontal Field of view."]
32947 pub hfov: u16,
32948 #[doc = "Video Stream ID (1 for first, 2 for second, etc.)"]
32949 pub stream_id: u8,
32950 #[doc = "Number of streams available."]
32951 pub count: u8,
32952 #[doc = "Type of stream."]
32953 pub mavtype: VideoStreamType,
32954 #[doc = "Stream name."]
32955 #[cfg_attr(feature = "ts", ts(type = "string"))]
32956 pub name: CharArray<32>,
32957 #[doc = "Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to)."]
32958 #[cfg_attr(feature = "ts", ts(type = "string"))]
32959 pub uri: CharArray<160>,
32960 #[doc = "Encoding of stream."]
32961 #[cfg_attr(feature = "serde", serde(default))]
32962 pub encoding: VideoStreamEncoding,
32963 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
32964 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
32965 pub camera_device_id: u8,
32966}
32967impl VIDEO_STREAM_INFORMATION_DATA {
32968 pub const ENCODED_LEN: usize = 215usize;
32969 pub const DEFAULT: Self = Self {
32970 framerate: 0.0_f32,
32971 bitrate: 0_u32,
32972 flags: VideoStreamStatusFlags::DEFAULT,
32973 resolution_h: 0_u16,
32974 resolution_v: 0_u16,
32975 rotation: 0_u16,
32976 hfov: 0_u16,
32977 stream_id: 0_u8,
32978 count: 0_u8,
32979 mavtype: VideoStreamType::DEFAULT,
32980 name: CharArray::new([0_u8; 32usize]),
32981 uri: CharArray::new([0_u8; 160usize]),
32982 encoding: VideoStreamEncoding::DEFAULT,
32983 camera_device_id: 0_u8,
32984 };
32985 #[cfg(feature = "arbitrary")]
32986 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
32987 use arbitrary::{Arbitrary, Unstructured};
32988 let mut buf = [0u8; 1024];
32989 rng.fill_bytes(&mut buf);
32990 let mut unstructured = Unstructured::new(&buf);
32991 Self::arbitrary(&mut unstructured).unwrap_or_default()
32992 }
32993}
32994impl Default for VIDEO_STREAM_INFORMATION_DATA {
32995 fn default() -> Self {
32996 Self::DEFAULT.clone()
32997 }
32998}
32999impl MessageData for VIDEO_STREAM_INFORMATION_DATA {
33000 type Message = MavMessage;
33001 const ID: u32 = 269u32;
33002 const NAME: &'static str = "VIDEO_STREAM_INFORMATION";
33003 const EXTRA_CRC: u8 = 109u8;
33004 const ENCODED_LEN: usize = 215usize;
33005 fn deser(
33006 _version: MavlinkVersion,
33007 __input: &[u8],
33008 ) -> Result<Self, ::mavlink_core::error::ParserError> {
33009 let avail_len = __input.len();
33010 let mut payload_buf = [0; Self::ENCODED_LEN];
33011 let mut buf = if avail_len < Self::ENCODED_LEN {
33012 payload_buf[0..avail_len].copy_from_slice(__input);
33013 Bytes::new(&payload_buf)
33014 } else {
33015 Bytes::new(__input)
33016 };
33017 let mut __struct = Self::default();
33018 __struct.framerate = buf.get_f32_le()?;
33019 __struct.bitrate = buf.get_u32_le()?;
33020 let tmp = buf.get_u16_le()?;
33021 __struct.flags =
33022 VideoStreamStatusFlags::from_bits(tmp as <VideoStreamStatusFlags as Flags>::Bits)
33023 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
33024 flag_type: "VideoStreamStatusFlags",
33025 value: tmp as u64,
33026 })?;
33027 __struct.resolution_h = buf.get_u16_le()?;
33028 __struct.resolution_v = buf.get_u16_le()?;
33029 __struct.rotation = buf.get_u16_le()?;
33030 __struct.hfov = buf.get_u16_le()?;
33031 __struct.stream_id = buf.get_u8()?;
33032 __struct.count = buf.get_u8()?;
33033 let tmp = buf.get_u8()?;
33034 __struct.mavtype =
33035 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
33036 enum_type: "VideoStreamType",
33037 value: tmp as u64,
33038 })?;
33039 let mut tmp = [0_u8; 32usize];
33040 for v in &mut tmp {
33041 *v = buf.get_u8()?;
33042 }
33043 __struct.name = CharArray::new(tmp);
33044 let mut tmp = [0_u8; 160usize];
33045 for v in &mut tmp {
33046 *v = buf.get_u8()?;
33047 }
33048 __struct.uri = CharArray::new(tmp);
33049 let tmp = buf.get_u8()?;
33050 __struct.encoding =
33051 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
33052 enum_type: "VideoStreamEncoding",
33053 value: tmp as u64,
33054 })?;
33055 __struct.camera_device_id = buf.get_u8()?;
33056 Ok(__struct)
33057 }
33058 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
33059 let mut __tmp = BytesMut::new(bytes);
33060 #[allow(clippy::absurd_extreme_comparisons)]
33061 #[allow(unused_comparisons)]
33062 if __tmp.remaining() < Self::ENCODED_LEN {
33063 panic!(
33064 "buffer is too small (need {} bytes, but got {})",
33065 Self::ENCODED_LEN,
33066 __tmp.remaining(),
33067 )
33068 }
33069 __tmp.put_f32_le(self.framerate);
33070 __tmp.put_u32_le(self.bitrate);
33071 __tmp.put_u16_le(self.flags.bits() as u16);
33072 __tmp.put_u16_le(self.resolution_h);
33073 __tmp.put_u16_le(self.resolution_v);
33074 __tmp.put_u16_le(self.rotation);
33075 __tmp.put_u16_le(self.hfov);
33076 __tmp.put_u8(self.stream_id);
33077 __tmp.put_u8(self.count);
33078 __tmp.put_u8(self.mavtype as u8);
33079 for val in &self.name {
33080 __tmp.put_u8(*val);
33081 }
33082 for val in &self.uri {
33083 __tmp.put_u8(*val);
33084 }
33085 if matches!(version, MavlinkVersion::V2) {
33086 __tmp.put_u8(self.encoding as u8);
33087 __tmp.put_u8(self.camera_device_id);
33088 let len = __tmp.len();
33089 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
33090 } else {
33091 __tmp.len()
33092 }
33093 }
33094}
33095#[doc = "Information about the status of a video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE."]
33096#[doc = ""]
33097#[doc = "ID: 270"]
33098#[derive(Debug, Clone, PartialEq)]
33099#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
33100#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
33101#[cfg_attr(feature = "ts", derive(TS))]
33102#[cfg_attr(feature = "ts", ts(export))]
33103pub struct VIDEO_STREAM_STATUS_DATA {
33104 #[doc = "Frame rate"]
33105 pub framerate: f32,
33106 #[doc = "Bit rate"]
33107 pub bitrate: u32,
33108 #[doc = "Bitmap of stream status flags"]
33109 pub flags: VideoStreamStatusFlags,
33110 #[doc = "Horizontal resolution"]
33111 pub resolution_h: u16,
33112 #[doc = "Vertical resolution"]
33113 pub resolution_v: u16,
33114 #[doc = "Video image rotation clockwise"]
33115 pub rotation: u16,
33116 #[doc = "Horizontal Field of view"]
33117 pub hfov: u16,
33118 #[doc = "Video Stream ID (1 for first, 2 for second, etc.)"]
33119 pub stream_id: u8,
33120 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
33121 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
33122 pub camera_device_id: u8,
33123}
33124impl VIDEO_STREAM_STATUS_DATA {
33125 pub const ENCODED_LEN: usize = 20usize;
33126 pub const DEFAULT: Self = Self {
33127 framerate: 0.0_f32,
33128 bitrate: 0_u32,
33129 flags: VideoStreamStatusFlags::DEFAULT,
33130 resolution_h: 0_u16,
33131 resolution_v: 0_u16,
33132 rotation: 0_u16,
33133 hfov: 0_u16,
33134 stream_id: 0_u8,
33135 camera_device_id: 0_u8,
33136 };
33137 #[cfg(feature = "arbitrary")]
33138 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
33139 use arbitrary::{Arbitrary, Unstructured};
33140 let mut buf = [0u8; 1024];
33141 rng.fill_bytes(&mut buf);
33142 let mut unstructured = Unstructured::new(&buf);
33143 Self::arbitrary(&mut unstructured).unwrap_or_default()
33144 }
33145}
33146impl Default for VIDEO_STREAM_STATUS_DATA {
33147 fn default() -> Self {
33148 Self::DEFAULT.clone()
33149 }
33150}
33151impl MessageData for VIDEO_STREAM_STATUS_DATA {
33152 type Message = MavMessage;
33153 const ID: u32 = 270u32;
33154 const NAME: &'static str = "VIDEO_STREAM_STATUS";
33155 const EXTRA_CRC: u8 = 59u8;
33156 const ENCODED_LEN: usize = 20usize;
33157 fn deser(
33158 _version: MavlinkVersion,
33159 __input: &[u8],
33160 ) -> Result<Self, ::mavlink_core::error::ParserError> {
33161 let avail_len = __input.len();
33162 let mut payload_buf = [0; Self::ENCODED_LEN];
33163 let mut buf = if avail_len < Self::ENCODED_LEN {
33164 payload_buf[0..avail_len].copy_from_slice(__input);
33165 Bytes::new(&payload_buf)
33166 } else {
33167 Bytes::new(__input)
33168 };
33169 let mut __struct = Self::default();
33170 __struct.framerate = buf.get_f32_le()?;
33171 __struct.bitrate = buf.get_u32_le()?;
33172 let tmp = buf.get_u16_le()?;
33173 __struct.flags =
33174 VideoStreamStatusFlags::from_bits(tmp as <VideoStreamStatusFlags as Flags>::Bits)
33175 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
33176 flag_type: "VideoStreamStatusFlags",
33177 value: tmp as u64,
33178 })?;
33179 __struct.resolution_h = buf.get_u16_le()?;
33180 __struct.resolution_v = buf.get_u16_le()?;
33181 __struct.rotation = buf.get_u16_le()?;
33182 __struct.hfov = buf.get_u16_le()?;
33183 __struct.stream_id = buf.get_u8()?;
33184 __struct.camera_device_id = buf.get_u8()?;
33185 Ok(__struct)
33186 }
33187 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
33188 let mut __tmp = BytesMut::new(bytes);
33189 #[allow(clippy::absurd_extreme_comparisons)]
33190 #[allow(unused_comparisons)]
33191 if __tmp.remaining() < Self::ENCODED_LEN {
33192 panic!(
33193 "buffer is too small (need {} bytes, but got {})",
33194 Self::ENCODED_LEN,
33195 __tmp.remaining(),
33196 )
33197 }
33198 __tmp.put_f32_le(self.framerate);
33199 __tmp.put_u32_le(self.bitrate);
33200 __tmp.put_u16_le(self.flags.bits() as u16);
33201 __tmp.put_u16_le(self.resolution_h);
33202 __tmp.put_u16_le(self.resolution_v);
33203 __tmp.put_u16_le(self.rotation);
33204 __tmp.put_u16_le(self.hfov);
33205 __tmp.put_u8(self.stream_id);
33206 if matches!(version, MavlinkVersion::V2) {
33207 __tmp.put_u8(self.camera_device_id);
33208 let len = __tmp.len();
33209 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
33210 } else {
33211 __tmp.len()
33212 }
33213 }
33214}
33215#[doc = "Local position/attitude estimate from a vision source."]
33216#[doc = ""]
33217#[doc = "ID: 102"]
33218#[derive(Debug, Clone, PartialEq)]
33219#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
33220#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
33221#[cfg_attr(feature = "ts", derive(TS))]
33222#[cfg_attr(feature = "ts", ts(export))]
33223pub struct VISION_POSITION_ESTIMATE_DATA {
33224 #[doc = "Timestamp (UNIX time or time since system boot)"]
33225 pub usec: u64,
33226 #[doc = "Local X position"]
33227 pub x: f32,
33228 #[doc = "Local Y position"]
33229 pub y: f32,
33230 #[doc = "Local Z position"]
33231 pub z: f32,
33232 #[doc = "Roll angle"]
33233 pub roll: f32,
33234 #[doc = "Pitch angle"]
33235 pub pitch: f32,
33236 #[doc = "Yaw angle"]
33237 pub yaw: f32,
33238 #[doc = "Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
33239 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
33240 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
33241 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
33242 pub covariance: [f32; 21],
33243 #[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps."]
33244 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
33245 pub reset_counter: u8,
33246}
33247impl VISION_POSITION_ESTIMATE_DATA {
33248 pub const ENCODED_LEN: usize = 117usize;
33249 pub const DEFAULT: Self = Self {
33250 usec: 0_u64,
33251 x: 0.0_f32,
33252 y: 0.0_f32,
33253 z: 0.0_f32,
33254 roll: 0.0_f32,
33255 pitch: 0.0_f32,
33256 yaw: 0.0_f32,
33257 covariance: [0.0_f32; 21usize],
33258 reset_counter: 0_u8,
33259 };
33260 #[cfg(feature = "arbitrary")]
33261 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
33262 use arbitrary::{Arbitrary, Unstructured};
33263 let mut buf = [0u8; 1024];
33264 rng.fill_bytes(&mut buf);
33265 let mut unstructured = Unstructured::new(&buf);
33266 Self::arbitrary(&mut unstructured).unwrap_or_default()
33267 }
33268}
33269impl Default for VISION_POSITION_ESTIMATE_DATA {
33270 fn default() -> Self {
33271 Self::DEFAULT.clone()
33272 }
33273}
33274impl MessageData for VISION_POSITION_ESTIMATE_DATA {
33275 type Message = MavMessage;
33276 const ID: u32 = 102u32;
33277 const NAME: &'static str = "VISION_POSITION_ESTIMATE";
33278 const EXTRA_CRC: u8 = 158u8;
33279 const ENCODED_LEN: usize = 117usize;
33280 fn deser(
33281 _version: MavlinkVersion,
33282 __input: &[u8],
33283 ) -> Result<Self, ::mavlink_core::error::ParserError> {
33284 let avail_len = __input.len();
33285 let mut payload_buf = [0; Self::ENCODED_LEN];
33286 let mut buf = if avail_len < Self::ENCODED_LEN {
33287 payload_buf[0..avail_len].copy_from_slice(__input);
33288 Bytes::new(&payload_buf)
33289 } else {
33290 Bytes::new(__input)
33291 };
33292 let mut __struct = Self::default();
33293 __struct.usec = buf.get_u64_le()?;
33294 __struct.x = buf.get_f32_le()?;
33295 __struct.y = buf.get_f32_le()?;
33296 __struct.z = buf.get_f32_le()?;
33297 __struct.roll = buf.get_f32_le()?;
33298 __struct.pitch = buf.get_f32_le()?;
33299 __struct.yaw = buf.get_f32_le()?;
33300 for v in &mut __struct.covariance {
33301 let val = buf.get_f32_le()?;
33302 *v = val;
33303 }
33304 __struct.reset_counter = buf.get_u8()?;
33305 Ok(__struct)
33306 }
33307 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
33308 let mut __tmp = BytesMut::new(bytes);
33309 #[allow(clippy::absurd_extreme_comparisons)]
33310 #[allow(unused_comparisons)]
33311 if __tmp.remaining() < Self::ENCODED_LEN {
33312 panic!(
33313 "buffer is too small (need {} bytes, but got {})",
33314 Self::ENCODED_LEN,
33315 __tmp.remaining(),
33316 )
33317 }
33318 __tmp.put_u64_le(self.usec);
33319 __tmp.put_f32_le(self.x);
33320 __tmp.put_f32_le(self.y);
33321 __tmp.put_f32_le(self.z);
33322 __tmp.put_f32_le(self.roll);
33323 __tmp.put_f32_le(self.pitch);
33324 __tmp.put_f32_le(self.yaw);
33325 if matches!(version, MavlinkVersion::V2) {
33326 for val in &self.covariance {
33327 __tmp.put_f32_le(*val);
33328 }
33329 __tmp.put_u8(self.reset_counter);
33330 let len = __tmp.len();
33331 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
33332 } else {
33333 __tmp.len()
33334 }
33335 }
33336}
33337#[doc = "Speed estimate from a vision source."]
33338#[doc = ""]
33339#[doc = "ID: 103"]
33340#[derive(Debug, Clone, PartialEq)]
33341#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
33342#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
33343#[cfg_attr(feature = "ts", derive(TS))]
33344#[cfg_attr(feature = "ts", ts(export))]
33345pub struct VISION_SPEED_ESTIMATE_DATA {
33346 #[doc = "Timestamp (UNIX time or time since system boot)"]
33347 pub usec: u64,
33348 #[doc = "Global X speed"]
33349 pub x: f32,
33350 #[doc = "Global Y speed"]
33351 pub y: f32,
33352 #[doc = "Global Z speed"]
33353 pub z: f32,
33354 #[doc = "Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array."]
33355 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
33356 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
33357 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
33358 pub covariance: [f32; 9],
33359 #[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps."]
33360 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
33361 pub reset_counter: u8,
33362}
33363impl VISION_SPEED_ESTIMATE_DATA {
33364 pub const ENCODED_LEN: usize = 57usize;
33365 pub const DEFAULT: Self = Self {
33366 usec: 0_u64,
33367 x: 0.0_f32,
33368 y: 0.0_f32,
33369 z: 0.0_f32,
33370 covariance: [0.0_f32; 9usize],
33371 reset_counter: 0_u8,
33372 };
33373 #[cfg(feature = "arbitrary")]
33374 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
33375 use arbitrary::{Arbitrary, Unstructured};
33376 let mut buf = [0u8; 1024];
33377 rng.fill_bytes(&mut buf);
33378 let mut unstructured = Unstructured::new(&buf);
33379 Self::arbitrary(&mut unstructured).unwrap_or_default()
33380 }
33381}
33382impl Default for VISION_SPEED_ESTIMATE_DATA {
33383 fn default() -> Self {
33384 Self::DEFAULT.clone()
33385 }
33386}
33387impl MessageData for VISION_SPEED_ESTIMATE_DATA {
33388 type Message = MavMessage;
33389 const ID: u32 = 103u32;
33390 const NAME: &'static str = "VISION_SPEED_ESTIMATE";
33391 const EXTRA_CRC: u8 = 208u8;
33392 const ENCODED_LEN: usize = 57usize;
33393 fn deser(
33394 _version: MavlinkVersion,
33395 __input: &[u8],
33396 ) -> Result<Self, ::mavlink_core::error::ParserError> {
33397 let avail_len = __input.len();
33398 let mut payload_buf = [0; Self::ENCODED_LEN];
33399 let mut buf = if avail_len < Self::ENCODED_LEN {
33400 payload_buf[0..avail_len].copy_from_slice(__input);
33401 Bytes::new(&payload_buf)
33402 } else {
33403 Bytes::new(__input)
33404 };
33405 let mut __struct = Self::default();
33406 __struct.usec = buf.get_u64_le()?;
33407 __struct.x = buf.get_f32_le()?;
33408 __struct.y = buf.get_f32_le()?;
33409 __struct.z = buf.get_f32_le()?;
33410 for v in &mut __struct.covariance {
33411 let val = buf.get_f32_le()?;
33412 *v = val;
33413 }
33414 __struct.reset_counter = buf.get_u8()?;
33415 Ok(__struct)
33416 }
33417 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
33418 let mut __tmp = BytesMut::new(bytes);
33419 #[allow(clippy::absurd_extreme_comparisons)]
33420 #[allow(unused_comparisons)]
33421 if __tmp.remaining() < Self::ENCODED_LEN {
33422 panic!(
33423 "buffer is too small (need {} bytes, but got {})",
33424 Self::ENCODED_LEN,
33425 __tmp.remaining(),
33426 )
33427 }
33428 __tmp.put_u64_le(self.usec);
33429 __tmp.put_f32_le(self.x);
33430 __tmp.put_f32_le(self.y);
33431 __tmp.put_f32_le(self.z);
33432 if matches!(version, MavlinkVersion::V2) {
33433 for val in &self.covariance {
33434 __tmp.put_f32_le(*val);
33435 }
33436 __tmp.put_u8(self.reset_counter);
33437 let len = __tmp.len();
33438 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
33439 } else {
33440 __tmp.len()
33441 }
33442 }
33443}
33444#[doc = "Cumulative distance traveled for each reported wheel."]
33445#[doc = ""]
33446#[doc = "ID: 9000"]
33447#[derive(Debug, Clone, PartialEq)]
33448#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
33449#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
33450#[cfg_attr(feature = "ts", derive(TS))]
33451#[cfg_attr(feature = "ts", ts(export))]
33452pub struct WHEEL_DISTANCE_DATA {
33453 #[doc = "Timestamp (synced to UNIX time or since system boot)."]
33454 pub time_usec: u64,
33455 #[doc = "Distance reported by individual wheel encoders. Forward rotations increase values, reverse rotations decrease them. Not all wheels will necessarily have wheel encoders; the mapping of encoders to wheel positions must be agreed/understood by the endpoints."]
33456 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
33457 #[cfg_attr(feature = "ts", ts(type = "Array<number>"))]
33458 pub distance: [f64; 16],
33459 #[doc = "Number of wheels reported."]
33460 pub count: u8,
33461}
33462impl WHEEL_DISTANCE_DATA {
33463 pub const ENCODED_LEN: usize = 137usize;
33464 pub const DEFAULT: Self = Self {
33465 time_usec: 0_u64,
33466 distance: [0.0_f64; 16usize],
33467 count: 0_u8,
33468 };
33469 #[cfg(feature = "arbitrary")]
33470 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
33471 use arbitrary::{Arbitrary, Unstructured};
33472 let mut buf = [0u8; 1024];
33473 rng.fill_bytes(&mut buf);
33474 let mut unstructured = Unstructured::new(&buf);
33475 Self::arbitrary(&mut unstructured).unwrap_or_default()
33476 }
33477}
33478impl Default for WHEEL_DISTANCE_DATA {
33479 fn default() -> Self {
33480 Self::DEFAULT.clone()
33481 }
33482}
33483impl MessageData for WHEEL_DISTANCE_DATA {
33484 type Message = MavMessage;
33485 const ID: u32 = 9000u32;
33486 const NAME: &'static str = "WHEEL_DISTANCE";
33487 const EXTRA_CRC: u8 = 113u8;
33488 const ENCODED_LEN: usize = 137usize;
33489 fn deser(
33490 _version: MavlinkVersion,
33491 __input: &[u8],
33492 ) -> Result<Self, ::mavlink_core::error::ParserError> {
33493 let avail_len = __input.len();
33494 let mut payload_buf = [0; Self::ENCODED_LEN];
33495 let mut buf = if avail_len < Self::ENCODED_LEN {
33496 payload_buf[0..avail_len].copy_from_slice(__input);
33497 Bytes::new(&payload_buf)
33498 } else {
33499 Bytes::new(__input)
33500 };
33501 let mut __struct = Self::default();
33502 __struct.time_usec = buf.get_u64_le()?;
33503 for v in &mut __struct.distance {
33504 let val = buf.get_f64_le()?;
33505 *v = val;
33506 }
33507 __struct.count = buf.get_u8()?;
33508 Ok(__struct)
33509 }
33510 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
33511 let mut __tmp = BytesMut::new(bytes);
33512 #[allow(clippy::absurd_extreme_comparisons)]
33513 #[allow(unused_comparisons)]
33514 if __tmp.remaining() < Self::ENCODED_LEN {
33515 panic!(
33516 "buffer is too small (need {} bytes, but got {})",
33517 Self::ENCODED_LEN,
33518 __tmp.remaining(),
33519 )
33520 }
33521 __tmp.put_u64_le(self.time_usec);
33522 for val in &self.distance {
33523 __tmp.put_f64_le(*val);
33524 }
33525 __tmp.put_u8(self.count);
33526 if matches!(version, MavlinkVersion::V2) {
33527 let len = __tmp.len();
33528 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
33529 } else {
33530 __tmp.len()
33531 }
33532 }
33533}
33534#[doc = "Configure WiFi AP SSID, password, and mode. This message is re-emitted as an acknowledgement by the AP. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE."]
33535#[doc = ""]
33536#[doc = "ID: 299"]
33537#[derive(Debug, Clone, PartialEq)]
33538#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
33539#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
33540#[cfg_attr(feature = "ts", derive(TS))]
33541#[cfg_attr(feature = "ts", ts(export))]
33542pub struct WIFI_CONFIG_AP_DATA {
33543 #[doc = "Name of Wi-Fi network (SSID). Blank to leave it unchanged when setting. Current SSID when sent back as a response."]
33544 #[cfg_attr(feature = "ts", ts(type = "string"))]
33545 pub ssid: CharArray<32>,
33546 #[doc = "Password. Blank for an open AP. MD5 hash when message is sent back as a response."]
33547 #[cfg_attr(feature = "ts", ts(type = "string"))]
33548 pub password: CharArray<64>,
33549 #[doc = "WiFi Mode."]
33550 #[cfg_attr(feature = "serde", serde(default))]
33551 pub mode: WifiConfigApMode,
33552 #[doc = "Message acceptance response (sent back to GS)."]
33553 #[cfg_attr(feature = "serde", serde(default))]
33554 pub response: WifiConfigApResponse,
33555}
33556impl WIFI_CONFIG_AP_DATA {
33557 pub const ENCODED_LEN: usize = 98usize;
33558 pub const DEFAULT: Self = Self {
33559 ssid: CharArray::new([0_u8; 32usize]),
33560 password: CharArray::new([0_u8; 64usize]),
33561 mode: WifiConfigApMode::DEFAULT,
33562 response: WifiConfigApResponse::DEFAULT,
33563 };
33564 #[cfg(feature = "arbitrary")]
33565 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
33566 use arbitrary::{Arbitrary, Unstructured};
33567 let mut buf = [0u8; 1024];
33568 rng.fill_bytes(&mut buf);
33569 let mut unstructured = Unstructured::new(&buf);
33570 Self::arbitrary(&mut unstructured).unwrap_or_default()
33571 }
33572}
33573impl Default for WIFI_CONFIG_AP_DATA {
33574 fn default() -> Self {
33575 Self::DEFAULT.clone()
33576 }
33577}
33578impl MessageData for WIFI_CONFIG_AP_DATA {
33579 type Message = MavMessage;
33580 const ID: u32 = 299u32;
33581 const NAME: &'static str = "WIFI_CONFIG_AP";
33582 const EXTRA_CRC: u8 = 19u8;
33583 const ENCODED_LEN: usize = 98usize;
33584 fn deser(
33585 _version: MavlinkVersion,
33586 __input: &[u8],
33587 ) -> Result<Self, ::mavlink_core::error::ParserError> {
33588 let avail_len = __input.len();
33589 let mut payload_buf = [0; Self::ENCODED_LEN];
33590 let mut buf = if avail_len < Self::ENCODED_LEN {
33591 payload_buf[0..avail_len].copy_from_slice(__input);
33592 Bytes::new(&payload_buf)
33593 } else {
33594 Bytes::new(__input)
33595 };
33596 let mut __struct = Self::default();
33597 let mut tmp = [0_u8; 32usize];
33598 for v in &mut tmp {
33599 *v = buf.get_u8()?;
33600 }
33601 __struct.ssid = CharArray::new(tmp);
33602 let mut tmp = [0_u8; 64usize];
33603 for v in &mut tmp {
33604 *v = buf.get_u8()?;
33605 }
33606 __struct.password = CharArray::new(tmp);
33607 let tmp = buf.get_i8()?;
33608 __struct.mode =
33609 FromPrimitive::from_i8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
33610 enum_type: "WifiConfigApMode",
33611 value: tmp as u64,
33612 })?;
33613 let tmp = buf.get_i8()?;
33614 __struct.response =
33615 FromPrimitive::from_i8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
33616 enum_type: "WifiConfigApResponse",
33617 value: tmp as u64,
33618 })?;
33619 Ok(__struct)
33620 }
33621 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
33622 let mut __tmp = BytesMut::new(bytes);
33623 #[allow(clippy::absurd_extreme_comparisons)]
33624 #[allow(unused_comparisons)]
33625 if __tmp.remaining() < Self::ENCODED_LEN {
33626 panic!(
33627 "buffer is too small (need {} bytes, but got {})",
33628 Self::ENCODED_LEN,
33629 __tmp.remaining(),
33630 )
33631 }
33632 for val in &self.ssid {
33633 __tmp.put_u8(*val);
33634 }
33635 for val in &self.password {
33636 __tmp.put_u8(*val);
33637 }
33638 if matches!(version, MavlinkVersion::V2) {
33639 __tmp.put_i8(self.mode as i8);
33640 __tmp.put_i8(self.response as i8);
33641 let len = __tmp.len();
33642 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
33643 } else {
33644 __tmp.len()
33645 }
33646 }
33647}
33648#[doc = "Winch status."]
33649#[doc = ""]
33650#[doc = "ID: 9005"]
33651#[derive(Debug, Clone, PartialEq)]
33652#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
33653#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
33654#[cfg_attr(feature = "ts", derive(TS))]
33655#[cfg_attr(feature = "ts", ts(export))]
33656pub struct WINCH_STATUS_DATA {
33657 #[doc = "Timestamp (synced to UNIX time or since system boot)."]
33658 pub time_usec: u64,
33659 #[doc = "Length of line released. NaN if unknown"]
33660 pub line_length: f32,
33661 #[doc = "Speed line is being released or retracted. Positive values if being released, negative values if being retracted, NaN if unknown"]
33662 pub speed: f32,
33663 #[doc = "Tension on the line. NaN if unknown"]
33664 pub tension: f32,
33665 #[doc = "Voltage of the battery supplying the winch. NaN if unknown"]
33666 pub voltage: f32,
33667 #[doc = "Current draw from the winch. NaN if unknown"]
33668 pub current: f32,
33669 #[doc = "Status flags"]
33670 pub status: MavWinchStatusFlag,
33671 #[doc = "Temperature of the motor. INT16_MAX if unknown"]
33672 pub temperature: i16,
33673}
33674impl WINCH_STATUS_DATA {
33675 pub const ENCODED_LEN: usize = 34usize;
33676 pub const DEFAULT: Self = Self {
33677 time_usec: 0_u64,
33678 line_length: 0.0_f32,
33679 speed: 0.0_f32,
33680 tension: 0.0_f32,
33681 voltage: 0.0_f32,
33682 current: 0.0_f32,
33683 status: MavWinchStatusFlag::DEFAULT,
33684 temperature: 0_i16,
33685 };
33686 #[cfg(feature = "arbitrary")]
33687 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
33688 use arbitrary::{Arbitrary, Unstructured};
33689 let mut buf = [0u8; 1024];
33690 rng.fill_bytes(&mut buf);
33691 let mut unstructured = Unstructured::new(&buf);
33692 Self::arbitrary(&mut unstructured).unwrap_or_default()
33693 }
33694}
33695impl Default for WINCH_STATUS_DATA {
33696 fn default() -> Self {
33697 Self::DEFAULT.clone()
33698 }
33699}
33700impl MessageData for WINCH_STATUS_DATA {
33701 type Message = MavMessage;
33702 const ID: u32 = 9005u32;
33703 const NAME: &'static str = "WINCH_STATUS";
33704 const EXTRA_CRC: u8 = 117u8;
33705 const ENCODED_LEN: usize = 34usize;
33706 fn deser(
33707 _version: MavlinkVersion,
33708 __input: &[u8],
33709 ) -> Result<Self, ::mavlink_core::error::ParserError> {
33710 let avail_len = __input.len();
33711 let mut payload_buf = [0; Self::ENCODED_LEN];
33712 let mut buf = if avail_len < Self::ENCODED_LEN {
33713 payload_buf[0..avail_len].copy_from_slice(__input);
33714 Bytes::new(&payload_buf)
33715 } else {
33716 Bytes::new(__input)
33717 };
33718 let mut __struct = Self::default();
33719 __struct.time_usec = buf.get_u64_le()?;
33720 __struct.line_length = buf.get_f32_le()?;
33721 __struct.speed = buf.get_f32_le()?;
33722 __struct.tension = buf.get_f32_le()?;
33723 __struct.voltage = buf.get_f32_le()?;
33724 __struct.current = buf.get_f32_le()?;
33725 let tmp = buf.get_u32_le()?;
33726 __struct.status = MavWinchStatusFlag::from_bits(tmp as <MavWinchStatusFlag as Flags>::Bits)
33727 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
33728 flag_type: "MavWinchStatusFlag",
33729 value: tmp as u64,
33730 })?;
33731 __struct.temperature = buf.get_i16_le()?;
33732 Ok(__struct)
33733 }
33734 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
33735 let mut __tmp = BytesMut::new(bytes);
33736 #[allow(clippy::absurd_extreme_comparisons)]
33737 #[allow(unused_comparisons)]
33738 if __tmp.remaining() < Self::ENCODED_LEN {
33739 panic!(
33740 "buffer is too small (need {} bytes, but got {})",
33741 Self::ENCODED_LEN,
33742 __tmp.remaining(),
33743 )
33744 }
33745 __tmp.put_u64_le(self.time_usec);
33746 __tmp.put_f32_le(self.line_length);
33747 __tmp.put_f32_le(self.speed);
33748 __tmp.put_f32_le(self.tension);
33749 __tmp.put_f32_le(self.voltage);
33750 __tmp.put_f32_le(self.current);
33751 __tmp.put_u32_le(self.status.bits() as u32);
33752 __tmp.put_i16_le(self.temperature);
33753 if matches!(version, MavlinkVersion::V2) {
33754 let len = __tmp.len();
33755 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
33756 } else {
33757 __tmp.len()
33758 }
33759 }
33760}
33761#[doc = "Wind estimate from vehicle. Note that despite the name, this message does not actually contain any covariances but instead variability and accuracy fields in terms of standard deviation (1-STD)."]
33762#[doc = ""]
33763#[doc = "ID: 231"]
33764#[derive(Debug, Clone, PartialEq)]
33765#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
33766#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
33767#[cfg_attr(feature = "ts", derive(TS))]
33768#[cfg_attr(feature = "ts", ts(export))]
33769pub struct WIND_COV_DATA {
33770 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
33771 pub time_usec: u64,
33772 #[doc = "Wind in North (NED) direction (NAN if unknown)"]
33773 pub wind_x: f32,
33774 #[doc = "Wind in East (NED) direction (NAN if unknown)"]
33775 pub wind_y: f32,
33776 #[doc = "Wind in down (NED) direction (NAN if unknown)"]
33777 pub wind_z: f32,
33778 #[doc = "Variability of wind in XY, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown)"]
33779 pub var_horiz: f32,
33780 #[doc = "Variability of wind in Z, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown)"]
33781 pub var_vert: f32,
33782 #[doc = "Altitude (MSL) that this measurement was taken at (NAN if unknown)"]
33783 pub wind_alt: f32,
33784 #[doc = "Horizontal speed 1-STD accuracy (0 if unknown)"]
33785 pub horiz_accuracy: f32,
33786 #[doc = "Vertical speed 1-STD accuracy (0 if unknown)"]
33787 pub vert_accuracy: f32,
33788}
33789impl WIND_COV_DATA {
33790 pub const ENCODED_LEN: usize = 40usize;
33791 pub const DEFAULT: Self = Self {
33792 time_usec: 0_u64,
33793 wind_x: 0.0_f32,
33794 wind_y: 0.0_f32,
33795 wind_z: 0.0_f32,
33796 var_horiz: 0.0_f32,
33797 var_vert: 0.0_f32,
33798 wind_alt: 0.0_f32,
33799 horiz_accuracy: 0.0_f32,
33800 vert_accuracy: 0.0_f32,
33801 };
33802 #[cfg(feature = "arbitrary")]
33803 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
33804 use arbitrary::{Arbitrary, Unstructured};
33805 let mut buf = [0u8; 1024];
33806 rng.fill_bytes(&mut buf);
33807 let mut unstructured = Unstructured::new(&buf);
33808 Self::arbitrary(&mut unstructured).unwrap_or_default()
33809 }
33810}
33811impl Default for WIND_COV_DATA {
33812 fn default() -> Self {
33813 Self::DEFAULT.clone()
33814 }
33815}
33816impl MessageData for WIND_COV_DATA {
33817 type Message = MavMessage;
33818 const ID: u32 = 231u32;
33819 const NAME: &'static str = "WIND_COV";
33820 const EXTRA_CRC: u8 = 105u8;
33821 const ENCODED_LEN: usize = 40usize;
33822 fn deser(
33823 _version: MavlinkVersion,
33824 __input: &[u8],
33825 ) -> Result<Self, ::mavlink_core::error::ParserError> {
33826 let avail_len = __input.len();
33827 let mut payload_buf = [0; Self::ENCODED_LEN];
33828 let mut buf = if avail_len < Self::ENCODED_LEN {
33829 payload_buf[0..avail_len].copy_from_slice(__input);
33830 Bytes::new(&payload_buf)
33831 } else {
33832 Bytes::new(__input)
33833 };
33834 let mut __struct = Self::default();
33835 __struct.time_usec = buf.get_u64_le()?;
33836 __struct.wind_x = buf.get_f32_le()?;
33837 __struct.wind_y = buf.get_f32_le()?;
33838 __struct.wind_z = buf.get_f32_le()?;
33839 __struct.var_horiz = buf.get_f32_le()?;
33840 __struct.var_vert = buf.get_f32_le()?;
33841 __struct.wind_alt = buf.get_f32_le()?;
33842 __struct.horiz_accuracy = buf.get_f32_le()?;
33843 __struct.vert_accuracy = buf.get_f32_le()?;
33844 Ok(__struct)
33845 }
33846 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
33847 let mut __tmp = BytesMut::new(bytes);
33848 #[allow(clippy::absurd_extreme_comparisons)]
33849 #[allow(unused_comparisons)]
33850 if __tmp.remaining() < Self::ENCODED_LEN {
33851 panic!(
33852 "buffer is too small (need {} bytes, but got {})",
33853 Self::ENCODED_LEN,
33854 __tmp.remaining(),
33855 )
33856 }
33857 __tmp.put_u64_le(self.time_usec);
33858 __tmp.put_f32_le(self.wind_x);
33859 __tmp.put_f32_le(self.wind_y);
33860 __tmp.put_f32_le(self.wind_z);
33861 __tmp.put_f32_le(self.var_horiz);
33862 __tmp.put_f32_le(self.var_vert);
33863 __tmp.put_f32_le(self.wind_alt);
33864 __tmp.put_f32_le(self.horiz_accuracy);
33865 __tmp.put_f32_le(self.vert_accuracy);
33866 if matches!(version, MavlinkVersion::V2) {
33867 let len = __tmp.len();
33868 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
33869 } else {
33870 __tmp.len()
33871 }
33872 }
33873}
33874#[derive(Clone, PartialEq, Debug)]
33875#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
33876#[cfg_attr(feature = "serde", serde(tag = "type"))]
33877#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
33878#[cfg_attr(feature = "ts", derive(TS))]
33879#[cfg_attr(feature = "ts", ts(export))]
33880#[repr(u32)]
33881pub enum MavMessage {
33882 #[doc = "Set the vehicle attitude and body angular rates."]
33883 #[doc = ""]
33884 #[doc = "ID: 140"]
33885 ACTUATOR_CONTROL_TARGET(ACTUATOR_CONTROL_TARGET_DATA),
33886 #[doc = "The raw values of the actuator outputs (e.g. on Pixhawk, from MAIN, AUX ports). This message supersedes SERVO_OUTPUT_RAW."]
33887 #[doc = ""]
33888 #[doc = "ID: 375"]
33889 ACTUATOR_OUTPUT_STATUS(ACTUATOR_OUTPUT_STATUS_DATA),
33890 #[doc = "The location and information of an ADSB vehicle."]
33891 #[doc = ""]
33892 #[doc = "ID: 246"]
33893 ADSB_VEHICLE(ADSB_VEHICLE_DATA),
33894 #[doc = "The location and information of an AIS vessel."]
33895 #[doc = ""]
33896 #[doc = "ID: 301"]
33897 AIS_VESSEL(AIS_VESSEL_DATA),
33898 #[doc = "The current system altitude."]
33899 #[doc = ""]
33900 #[doc = "ID: 141"]
33901 ALTITUDE(ALTITUDE_DATA),
33902 #[doc = "The attitude in the aeronautical frame (right-handed, Z-down, Y-right, X-front, ZYX, intrinsic)."]
33903 #[doc = ""]
33904 #[doc = "ID: 30"]
33905 ATTITUDE(ATTITUDE_DATA),
33906 #[doc = "The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0)."]
33907 #[doc = ""]
33908 #[doc = "ID: 31"]
33909 ATTITUDE_QUATERNION(ATTITUDE_QUATERNION_DATA),
33910 #[doc = "The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0)."]
33911 #[doc = ""]
33912 #[doc = "ID: 61"]
33913 ATTITUDE_QUATERNION_COV(ATTITUDE_QUATERNION_COV_DATA),
33914 #[doc = "Reports the current commanded attitude of the vehicle as specified by the autopilot. This should match the commands sent in a SET_ATTITUDE_TARGET message if the vehicle is being controlled this way."]
33915 #[doc = ""]
33916 #[doc = "ID: 83"]
33917 ATTITUDE_TARGET(ATTITUDE_TARGET_DATA),
33918 #[doc = "Motion capture attitude and position."]
33919 #[doc = ""]
33920 #[doc = "ID: 138"]
33921 ATT_POS_MOCAP(ATT_POS_MOCAP_DATA),
33922 #[doc = "Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety."]
33923 #[doc = ""]
33924 #[doc = "ID: 7"]
33925 AUTH_KEY(AUTH_KEY_DATA),
33926 #[doc = "Low level message containing autopilot state relevant for a gimbal device. This message is to be sent from the autopilot to the gimbal device component. The data of this message are for the gimbal device's estimator corrections, in particular horizon compensation, as well as indicates autopilot control intentions, e.g. feed forward angular control in the z-axis."]
33927 #[doc = ""]
33928 #[doc = "ID: 286"]
33929 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA),
33930 #[doc = "Version and capability of autopilot software. This should be emitted in response to a request with MAV_CMD_REQUEST_MESSAGE."]
33931 #[doc = ""]
33932 #[doc = "ID: 148"]
33933 AUTOPILOT_VERSION(AUTOPILOT_VERSION_DATA),
33934 #[doc = "Information about a flight mode. The message can be enumerated to get information for all modes, or requested for a particular mode, using MAV_CMD_REQUEST_MESSAGE. Specify 0 in param2 to request that the message is emitted for all available modes or the specific index for just one mode. The modes must be available/settable for the current vehicle/frame type. Each mode should only be emitted once (even if it is both standard and custom). Note that the current mode should be emitted in CURRENT_MODE, and that if the mode list can change then AVAILABLE_MODES_MONITOR must be emitted on first change and subsequently streamed. See <https://mavlink.io/en/services/standard_modes.html>."]
33935 #[doc = ""]
33936 #[doc = "ID: 435"]
33937 AVAILABLE_MODES(AVAILABLE_MODES_DATA),
33938 #[doc = "A change to the sequence number indicates that the set of AVAILABLE_MODES has changed. A receiver must re-request all available modes whenever the sequence number changes. This is only emitted after the first change and should then be broadcast at low rate (nominally 0.3 Hz) and on change. See <https://mavlink.io/en/services/standard_modes.html>."]
33939 #[doc = ""]
33940 #[doc = "ID: 437"]
33941 AVAILABLE_MODES_MONITOR(AVAILABLE_MODES_MONITOR_DATA),
33942 #[doc = "Battery information that is static, or requires infrequent update. This message should requested using MAV_CMD_REQUEST_MESSAGE and/or streamed at very low rate. BATTERY_STATUS_V2 is used for higher-rate battery status information."]
33943 #[doc = ""]
33944 #[doc = "ID: 372"]
33945 BATTERY_INFO(BATTERY_INFO_DATA),
33946 #[doc = "Battery information. Updates GCS with flight controller battery status. Smart batteries also use this message, but may additionally send BATTERY_INFO."]
33947 #[doc = ""]
33948 #[doc = "ID: 147"]
33949 BATTERY_STATUS(BATTERY_STATUS_DATA),
33950 #[doc = "Report button state change."]
33951 #[doc = ""]
33952 #[doc = "ID: 257"]
33953 BUTTON_CHANGE(BUTTON_CHANGE_DATA),
33954 #[doc = "Information about the status of a capture. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
33955 #[doc = ""]
33956 #[doc = "ID: 262"]
33957 CAMERA_CAPTURE_STATUS(CAMERA_CAPTURE_STATUS_DATA),
33958 #[doc = "Information about the field of view of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
33959 #[doc = ""]
33960 #[doc = "ID: 271"]
33961 CAMERA_FOV_STATUS(CAMERA_FOV_STATUS_DATA),
33962 #[doc = "Information about a captured image. This is emitted every time a message is captured. MAV_CMD_REQUEST_MESSAGE can be used to (re)request this message for a specific sequence number or range of sequence numbers: MAV_CMD_REQUEST_MESSAGE.param2 indicates the sequence number the first image to send, or set to -1 to send the message for all sequence numbers. MAV_CMD_REQUEST_MESSAGE.param3 is used to specify a range of messages to send: set to 0 (default) to send just the the message for the sequence number in param 2, set to -1 to send the message for the sequence number in param 2 and all the following sequence numbers, set to the sequence number of the final message in the range."]
33963 #[doc = ""]
33964 #[doc = "ID: 263"]
33965 CAMERA_IMAGE_CAPTURED(CAMERA_IMAGE_CAPTURED_DATA),
33966 #[doc = "Information about a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
33967 #[doc = ""]
33968 #[doc = "ID: 259"]
33969 CAMERA_INFORMATION(CAMERA_INFORMATION_DATA),
33970 #[doc = "Settings of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
33971 #[doc = ""]
33972 #[doc = "ID: 260"]
33973 CAMERA_SETTINGS(CAMERA_SETTINGS_DATA),
33974 #[doc = "Camera absolute thermal range. This can be streamed when the associated VIDEO_STREAM_STATUS `flag` field bit VIDEO_STREAM_STATUS_FLAGS_THERMAL_RANGE_ENABLED is set, but a GCS may choose to only request it for the current active stream. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval (param3 indicates the stream id of the current camera, or 0 for all streams, param4 indicates the target camera_device_id for autopilot-attached cameras or 0 for MAVLink cameras)."]
33975 #[doc = ""]
33976 #[doc = "ID: 277"]
33977 CAMERA_THERMAL_RANGE(CAMERA_THERMAL_RANGE_DATA),
33978 #[doc = "Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval."]
33979 #[doc = ""]
33980 #[doc = "ID: 276"]
33981 CAMERA_TRACKING_GEO_STATUS(CAMERA_TRACKING_GEO_STATUS_DATA),
33982 #[doc = "Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval."]
33983 #[doc = ""]
33984 #[doc = "ID: 275"]
33985 CAMERA_TRACKING_IMAGE_STATUS(CAMERA_TRACKING_IMAGE_STATUS_DATA),
33986 #[doc = "Camera-IMU triggering and synchronisation message."]
33987 #[doc = ""]
33988 #[doc = "ID: 112"]
33989 CAMERA_TRIGGER(CAMERA_TRIGGER_DATA),
33990 #[doc = "A forwarded CANFD frame as requested by MAV_CMD_CAN_FORWARD. These are separated from CAN_FRAME as they need different handling (eg. TAO handling)."]
33991 #[doc = ""]
33992 #[doc = "ID: 387"]
33993 CANFD_FRAME(CANFD_FRAME_DATA),
33994 #[doc = "Modify the filter of what CAN messages to forward over the mavlink. This can be used to make CAN forwarding work well on low bandwidth links. The filtering is applied on bits 8 to 24 of the CAN id (2nd and 3rd bytes) which corresponds to the DroneCAN message ID for DroneCAN. Filters with more than 16 IDs can be constructed by sending multiple CAN_FILTER_MODIFY messages."]
33995 #[doc = ""]
33996 #[doc = "ID: 388"]
33997 CAN_FILTER_MODIFY(CAN_FILTER_MODIFY_DATA),
33998 #[doc = "A forwarded CAN frame as requested by MAV_CMD_CAN_FORWARD."]
33999 #[doc = ""]
34000 #[doc = "ID: 386"]
34001 CAN_FRAME(CAN_FRAME_DATA),
34002 #[doc = "Configure cellular modems. This message is re-emitted as an acknowledgement by the modem. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE."]
34003 #[doc = ""]
34004 #[doc = "ID: 336"]
34005 CELLULAR_CONFIG(CELLULAR_CONFIG_DATA),
34006 #[doc = "Report current used cellular network status."]
34007 #[doc = ""]
34008 #[doc = "ID: 334"]
34009 CELLULAR_STATUS(CELLULAR_STATUS_DATA),
34010 #[doc = "Request to control this MAV."]
34011 #[doc = ""]
34012 #[doc = "ID: 5"]
34013 CHANGE_OPERATOR_CONTROL(CHANGE_OPERATOR_CONTROL_DATA),
34014 #[doc = "Accept / deny control of this MAV."]
34015 #[doc = ""]
34016 #[doc = "ID: 6"]
34017 CHANGE_OPERATOR_CONTROL_ACK(CHANGE_OPERATOR_CONTROL_ACK_DATA),
34018 #[doc = "Information about a potential collision."]
34019 #[doc = ""]
34020 #[doc = "ID: 247"]
34021 COLLISION(COLLISION_DATA),
34022 #[doc = "Report status of a command. Includes feedback whether the command was executed. The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
34023 #[doc = ""]
34024 #[doc = "ID: 77"]
34025 COMMAND_ACK(COMMAND_ACK_DATA),
34026 #[doc = "Cancel a long running command. The target system should respond with a COMMAND_ACK to the original command with result=MAV_RESULT_CANCELLED if the long running process was cancelled. If it has already completed, the cancel action can be ignored. The cancel action can be retried until some sort of acknowledgement to the original command has been received. The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
34027 #[doc = ""]
34028 #[doc = "ID: 80"]
34029 COMMAND_CANCEL(COMMAND_CANCEL_DATA),
34030 #[doc = "Send a command with up to seven parameters to the MAV, where params 5 and 6 are integers and the other values are floats. This is preferred over COMMAND_LONG as it allows the MAV_FRAME to be specified for interpreting positional information, such as altitude. COMMAND_INT is also preferred when sending latitude and longitude data in params 5 and 6, as it allows for greater precision. Param 5 and 6 encode positional data as scaled integers, where the scaling depends on the actual command value. NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
34031 #[doc = ""]
34032 #[doc = "ID: 75"]
34033 COMMAND_INT(COMMAND_INT_DATA),
34034 #[doc = "Send a command with up to seven parameters to the MAV. COMMAND_INT is generally preferred when sending MAV_CMD commands that include positional information; it offers higher precision and allows the MAV_FRAME to be specified (which may otherwise be ambiguous, particularly for altitude). The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
34035 #[doc = ""]
34036 #[doc = "ID: 76"]
34037 COMMAND_LONG(COMMAND_LONG_DATA),
34038 #[doc = "Component information message, which may be requested using MAV_CMD_REQUEST_MESSAGE."]
34039 #[doc = ""]
34040 #[doc = "ID: 395"]
34041 #[deprecated = " See `COMPONENT_METADATA` (Deprecated since 2022-04)"]
34042 COMPONENT_INFORMATION(COMPONENT_INFORMATION_DATA),
34043 #[doc = "Basic component information data. Should be requested using MAV_CMD_REQUEST_MESSAGE on startup, or when required."]
34044 #[doc = ""]
34045 #[doc = "ID: 396"]
34046 COMPONENT_INFORMATION_BASIC(COMPONENT_INFORMATION_BASIC_DATA),
34047 #[doc = "Component metadata message, which may be requested using MAV_CMD_REQUEST_MESSAGE. This contains the MAVLink FTP URI and CRC for the component's general metadata file. The file must be hosted on the component, and may be xz compressed. The file CRC can be used for file caching. The general metadata file can be read to get the locations of other metadata files (COMP_METADATA_TYPE) and translations, which may be hosted either on the vehicle or the internet. For more information see: <https://mavlink.io/en/services/component_information.html>. Note: Camera components should use CAMERA_INFORMATION instead, and autopilots may use both this message and AUTOPILOT_VERSION."]
34048 #[doc = ""]
34049 #[doc = "ID: 397"]
34050 COMPONENT_METADATA(COMPONENT_METADATA_DATA),
34051 #[doc = "The smoothed, monotonic system state used to feed the control loops of the system."]
34052 #[doc = ""]
34053 #[doc = "ID: 146"]
34054 CONTROL_SYSTEM_STATE(CONTROL_SYSTEM_STATE_DATA),
34055 #[doc = "Regular broadcast for the current latest event sequence number for a component. This is used to check for dropped events."]
34056 #[doc = ""]
34057 #[doc = "ID: 411"]
34058 CURRENT_EVENT_SEQUENCE(CURRENT_EVENT_SEQUENCE_DATA),
34059 #[doc = "Get the current mode. This should be emitted on any mode change, and broadcast at low rate (nominally 0.5 Hz). It may be requested using MAV_CMD_REQUEST_MESSAGE. See <https://mavlink.io/en/services/standard_modes.html>."]
34060 #[doc = ""]
34061 #[doc = "ID: 436"]
34062 CURRENT_MODE(CURRENT_MODE_DATA),
34063 #[doc = "Data stream status information."]
34064 #[doc = ""]
34065 #[doc = "ID: 67"]
34066 #[deprecated = " See `MESSAGE_INTERVAL` (Deprecated since 2015-08)"]
34067 DATA_STREAM(DATA_STREAM_DATA),
34068 #[doc = "Handshake message to initiate, control and stop image streaming when using the Image Transmission Protocol: <https://mavlink.io/en/services/image_transmission.html>."]
34069 #[doc = ""]
34070 #[doc = "ID: 130"]
34071 DATA_TRANSMISSION_HANDSHAKE(DATA_TRANSMISSION_HANDSHAKE_DATA),
34072 #[doc = "Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N."]
34073 #[doc = ""]
34074 #[doc = "ID: 254"]
34075 DEBUG(DEBUG_DATA),
34076 #[doc = "Large debug/prototyping array. The message uses the maximum available payload for data. The array_id and name fields are used to discriminate between messages in code and in user interfaces (respectively). Do not use in production code."]
34077 #[doc = ""]
34078 #[doc = "ID: 350"]
34079 DEBUG_FLOAT_ARRAY(DEBUG_FLOAT_ARRAY_DATA),
34080 #[doc = "To debug something using a named 3D vector."]
34081 #[doc = ""]
34082 #[doc = "ID: 250"]
34083 DEBUG_VECT(DEBUG_VECT_DATA),
34084 #[doc = "Distance sensor information for an onboard rangefinder."]
34085 #[doc = ""]
34086 #[doc = "ID: 132"]
34087 DISTANCE_SENSOR(DISTANCE_SENSOR_DATA),
34088 #[doc = "EFI status output."]
34089 #[doc = ""]
34090 #[doc = "ID: 225"]
34091 EFI_STATUS(EFI_STATUS_DATA),
34092 #[doc = "Data packet for images sent using the Image Transmission Protocol: <https://mavlink.io/en/services/image_transmission.html>."]
34093 #[doc = ""]
34094 #[doc = "ID: 131"]
34095 ENCAPSULATED_DATA(ENCAPSULATED_DATA_DATA),
34096 #[doc = "ESC information for lower rate streaming. Recommended streaming rate 1Hz. See ESC_STATUS for higher-rate ESC data."]
34097 #[doc = ""]
34098 #[doc = "ID: 290"]
34099 ESC_INFO(ESC_INFO_DATA),
34100 #[doc = "ESC information for higher rate streaming. Recommended streaming rate is ~10 Hz. Information that changes more slowly is sent in ESC_INFO. It should typically only be streamed on high-bandwidth links (i.e. to a companion computer)."]
34101 #[doc = ""]
34102 #[doc = "ID: 291"]
34103 ESC_STATUS(ESC_STATUS_DATA),
34104 #[doc = "Estimator status message including flags, innovation test ratios and estimated accuracies. The flags message is an integer bitmask containing information on which EKF outputs are valid. See the ESTIMATOR_STATUS_FLAGS enum definition for further information. The innovation test ratios show the magnitude of the sensor innovation divided by the innovation check threshold. Under normal operation the innovation test ratios should be below 0.5 with occasional values up to 1.0. Values greater than 1.0 should be rare under normal operation and indicate that a measurement has been rejected by the filter. The user should be notified if an innovation test ratio greater than 1.0 is recorded. Notifications for values in the range between 0.5 and 1.0 should be optional and controllable by the user."]
34105 #[doc = ""]
34106 #[doc = "ID: 230"]
34107 ESTIMATOR_STATUS(ESTIMATOR_STATUS_DATA),
34108 #[doc = "Event message. Each new event from a particular component gets a new sequence number. The same message might be sent multiple times if (re-)requested. Most events are broadcast, some can be specific to a target component (as receivers keep track of the sequence for missed events, all events need to be broadcast. Thus we use destination_component instead of target_component)."]
34109 #[doc = ""]
34110 #[doc = "ID: 410"]
34111 EVENT(EVENT_DATA),
34112 #[doc = "Provides state for additional features."]
34113 #[doc = ""]
34114 #[doc = "ID: 245"]
34115 EXTENDED_SYS_STATE(EXTENDED_SYS_STATE_DATA),
34116 #[doc = "Status of geo-fencing. Sent in extended status stream when fencing enabled."]
34117 #[doc = ""]
34118 #[doc = "ID: 162"]
34119 FENCE_STATUS(FENCE_STATUS_DATA),
34120 #[doc = "File transfer protocol message: <https://mavlink.io/en/services/ftp.html>."]
34121 #[doc = ""]
34122 #[doc = "ID: 110"]
34123 FILE_TRANSFER_PROTOCOL(FILE_TRANSFER_PROTOCOL_DATA),
34124 #[doc = "Flight information. This includes time since boot for arm, takeoff, and land, and a flight number. Takeoff and landing values reset to zero on arm. This can be requested using MAV_CMD_REQUEST_MESSAGE. Note, some fields are misnamed - timestamps are from boot (not UTC) and the flight_uuid is a sequence number."]
34125 #[doc = ""]
34126 #[doc = "ID: 264"]
34127 FLIGHT_INFORMATION(FLIGHT_INFORMATION_DATA),
34128 #[doc = "Current motion information from a designated system."]
34129 #[doc = ""]
34130 #[doc = "ID: 144"]
34131 FOLLOW_TARGET(FOLLOW_TARGET_DATA),
34132 #[doc = "Fuel status. This message provides \"generic\" fuel level information for in a GCS and for triggering failsafes in an autopilot. The fuel type and associated units for fields in this message are defined in the enum MAV_FUEL_TYPE. The reported `consumed_fuel` and `remaining_fuel` must only be supplied if measured: they must not be inferred from the `maximum_fuel` and the other value. A recipient can assume that if these fields are supplied they are accurate. If not provided, the recipient can infer `remaining_fuel` from `maximum_fuel` and `consumed_fuel` on the assumption that the fuel was initially at its maximum (this is what battery monitors assume). Note however that this is an assumption, and the UI should prompt the user appropriately (i.e. notify user that they should fill the tank before boot). This kind of information may also be sent in fuel-specific messages such as BATTERY_STATUS_V2. If both messages are sent for the same fuel system, the ids and corresponding information must match. This should be streamed (nominally at 0.1 Hz)."]
34133 #[doc = ""]
34134 #[doc = "ID: 371"]
34135 FUEL_STATUS(FUEL_STATUS_DATA),
34136 #[doc = "Telemetry of power generation system. Alternator or mechanical generator."]
34137 #[doc = ""]
34138 #[doc = "ID: 373"]
34139 GENERATOR_STATUS(GENERATOR_STATUS_DATA),
34140 #[doc = "Message reporting the status of a gimbal device. \t This message should be broadcast by a gimbal device component at a low regular rate (e.g. 5 Hz). \t For the angles encoded in the quaternion and the angular velocities holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). \t If neither of these flags are set, then (for backwards compatibility) it holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), \t else they are relative to the vehicle heading (vehicle frame). \t Other conditions of the flags are not allowed. \t The quaternion and angular velocities in the other frame can be calculated from delta_yaw and delta_yaw_velocity as \t q_earth = q_delta_yaw * q_vehicle and w_earth = w_delta_yaw_velocity + w_vehicle (if not NaN). \t If neither the GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME nor the GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME flag is set, \t then (for backwards compatibility) the data in the delta_yaw and delta_yaw_velocity fields are to be ignored. \t New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME, \t and always should set delta_yaw and delta_yaw_velocity either to the proper value or NaN."]
34141 #[doc = ""]
34142 #[doc = "ID: 285"]
34143 GIMBAL_DEVICE_ATTITUDE_STATUS(GIMBAL_DEVICE_ATTITUDE_STATUS_DATA),
34144 #[doc = "Information about a low level gimbal. This message should be requested by the gimbal manager or a ground station using MAV_CMD_REQUEST_MESSAGE. The maximum angles and rates are the limits by hardware. However, the limits by software used are likely different/smaller and dependent on mode/settings/etc.."]
34145 #[doc = ""]
34146 #[doc = "ID: 283"]
34147 GIMBAL_DEVICE_INFORMATION(GIMBAL_DEVICE_INFORMATION_DATA),
34148 #[doc = "Low level message to control a gimbal device's attitude. \t This message is to be sent from the gimbal manager to the gimbal device component. \t The quaternion and angular velocities can be set to NaN according to use case. \t For the angles encoded in the quaternion and the angular velocities holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). \t If neither of these flags are set, then (for backwards compatibility) it holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), \t else they are relative to the vehicle heading (vehicle frame). \t Setting both GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME and GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is not allowed. \t These rules are to ensure backwards compatibility. \t New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME."]
34149 #[doc = ""]
34150 #[doc = "ID: 284"]
34151 GIMBAL_DEVICE_SET_ATTITUDE(GIMBAL_DEVICE_SET_ATTITUDE_DATA),
34152 #[doc = "Information about a high level gimbal manager. This message should be requested by a ground station using MAV_CMD_REQUEST_MESSAGE."]
34153 #[doc = ""]
34154 #[doc = "ID: 280"]
34155 GIMBAL_MANAGER_INFORMATION(GIMBAL_MANAGER_INFORMATION_DATA),
34156 #[doc = "High level message to control a gimbal's attitude. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case."]
34157 #[doc = ""]
34158 #[doc = "ID: 282"]
34159 GIMBAL_MANAGER_SET_ATTITUDE(GIMBAL_MANAGER_SET_ATTITUDE_DATA),
34160 #[doc = "High level message to control a gimbal manually. The angles or angular rates are unitless; the actual rates will depend on internal gimbal manager settings/configuration (e.g. set by parameters). This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case."]
34161 #[doc = ""]
34162 #[doc = "ID: 288"]
34163 GIMBAL_MANAGER_SET_MANUAL_CONTROL(GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA),
34164 #[doc = "Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation."]
34165 #[doc = ""]
34166 #[doc = "ID: 287"]
34167 GIMBAL_MANAGER_SET_PITCHYAW(GIMBAL_MANAGER_SET_PITCHYAW_DATA),
34168 #[doc = "Current status about a high level gimbal manager. This message should be broadcast at a low regular rate (e.g. 5Hz)."]
34169 #[doc = ""]
34170 #[doc = "ID: 281"]
34171 GIMBAL_MANAGER_STATUS(GIMBAL_MANAGER_STATUS_DATA),
34172 #[doc = "The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient."]
34173 #[doc = ""]
34174 #[doc = "ID: 33"]
34175 GLOBAL_POSITION_INT(GLOBAL_POSITION_INT_DATA),
34176 #[doc = "The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient. NOTE: This message is intended for onboard networks / companion computers and higher-bandwidth links and optimized for accuracy and completeness. Please use the GLOBAL_POSITION_INT message for a minimal subset."]
34177 #[doc = ""]
34178 #[doc = "ID: 63"]
34179 GLOBAL_POSITION_INT_COV(GLOBAL_POSITION_INT_COV_DATA),
34180 #[doc = "Global position/attitude estimate from a vision source."]
34181 #[doc = ""]
34182 #[doc = "ID: 101"]
34183 GLOBAL_VISION_POSITION_ESTIMATE(GLOBAL_VISION_POSITION_ESTIMATE_DATA),
34184 #[doc = "Second GPS data."]
34185 #[doc = ""]
34186 #[doc = "ID: 124"]
34187 GPS2_RAW(GPS2_RAW_DATA),
34188 #[doc = "RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting."]
34189 #[doc = ""]
34190 #[doc = "ID: 128"]
34191 GPS2_RTK(GPS2_RTK_DATA),
34192 #[doc = "Publishes the GPS coordinates of the vehicle local origin (0,0,0) position. Emitted whenever a new GPS-Local position mapping is requested or set - e.g. following SET_GPS_GLOBAL_ORIGIN message."]
34193 #[doc = ""]
34194 #[doc = "ID: 49"]
34195 GPS_GLOBAL_ORIGIN(GPS_GLOBAL_ORIGIN_DATA),
34196 #[doc = "Data for injecting into the onboard GPS (used for DGPS)."]
34197 #[doc = ""]
34198 #[doc = "ID: 123"]
34199 #[deprecated = " See `GPS_RTCM_DATA` (Deprecated since 2022-05)"]
34200 GPS_INJECT_DATA(GPS_INJECT_DATA_DATA),
34201 #[doc = "GPS sensor input message. This is a raw sensor value sent by the GPS. This is NOT the global position estimate of the system."]
34202 #[doc = ""]
34203 #[doc = "ID: 232"]
34204 GPS_INPUT(GPS_INPUT_DATA),
34205 #[doc = "The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION_INT for the global position estimate."]
34206 #[doc = ""]
34207 #[doc = "ID: 24"]
34208 GPS_RAW_INT(GPS_RAW_INT_DATA),
34209 #[doc = "RTCM message for injecting into the onboard GPS (used for DGPS)."]
34210 #[doc = ""]
34211 #[doc = "ID: 233"]
34212 GPS_RTCM_DATA(GPS_RTCM_DATA_DATA),
34213 #[doc = "RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting."]
34214 #[doc = ""]
34215 #[doc = "ID: 127"]
34216 GPS_RTK(GPS_RTK_DATA),
34217 #[doc = "The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION_INT for the global position estimate. This message can contain information for up to 20 satellites."]
34218 #[doc = ""]
34219 #[doc = "ID: 25"]
34220 GPS_STATUS(GPS_STATUS_DATA),
34221 #[doc = "The heartbeat message shows that a system or component is present and responding. The type and autopilot fields (along with the message component id), allow the receiving system to treat further messages from this system appropriately (e.g. by laying out the user interface based on the autopilot). This microservice is documented at <https://mavlink.io/en/services/heartbeat.html>."]
34222 #[doc = ""]
34223 #[doc = "ID: 0"]
34224 HEARTBEAT(HEARTBEAT_DATA),
34225 #[doc = "The IMU readings in SI units in NED body frame."]
34226 #[doc = ""]
34227 #[doc = "ID: 105"]
34228 HIGHRES_IMU(HIGHRES_IMU_DATA),
34229 #[doc = "Message appropriate for high latency connections like Iridium."]
34230 #[doc = ""]
34231 #[doc = "ID: 234"]
34232 #[deprecated = " See `HIGH_LATENCY2` (Deprecated since 2020-10)"]
34233 HIGH_LATENCY(HIGH_LATENCY_DATA),
34234 #[doc = "Message appropriate for high latency connections like Iridium (version 2)."]
34235 #[doc = ""]
34236 #[doc = "ID: 235"]
34237 HIGH_LATENCY2(HIGH_LATENCY2_DATA),
34238 #[doc = "Sent from autopilot to simulation. Hardware in the loop control outputs. Alternative to HIL_CONTROLS."]
34239 #[doc = ""]
34240 #[doc = "ID: 93"]
34241 HIL_ACTUATOR_CONTROLS(HIL_ACTUATOR_CONTROLS_DATA),
34242 #[doc = "Sent from autopilot to simulation. Hardware in the loop control outputs. Alternative to HIL_ACTUATOR_CONTROLS."]
34243 #[doc = ""]
34244 #[doc = "ID: 91"]
34245 HIL_CONTROLS(HIL_CONTROLS_DATA),
34246 #[doc = "The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION_INT for the global position estimate."]
34247 #[doc = ""]
34248 #[doc = "ID: 113"]
34249 HIL_GPS(HIL_GPS_DATA),
34250 #[doc = "Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical mouse sensor)."]
34251 #[doc = ""]
34252 #[doc = "ID: 114"]
34253 HIL_OPTICAL_FLOW(HIL_OPTICAL_FLOW_DATA),
34254 #[doc = "Sent from simulation to autopilot. The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification."]
34255 #[doc = ""]
34256 #[doc = "ID: 92"]
34257 HIL_RC_INPUTS_RAW(HIL_RC_INPUTS_RAW_DATA),
34258 #[doc = "The IMU readings in SI units in NED body frame."]
34259 #[doc = ""]
34260 #[doc = "ID: 107"]
34261 HIL_SENSOR(HIL_SENSOR_DATA),
34262 #[doc = "Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations."]
34263 #[doc = ""]
34264 #[doc = "ID: 90"]
34265 #[deprecated = "Suffers from missing airspeed fields and singularities due to Euler angles. See `HIL_STATE_QUATERNION` (Deprecated since 2013-07)"]
34266 HIL_STATE(HIL_STATE_DATA),
34267 #[doc = "Sent from simulation to autopilot, avoids in contrast to HIL_STATE singularities. This packet is useful for high throughput applications such as hardware in the loop simulations."]
34268 #[doc = ""]
34269 #[doc = "ID: 115"]
34270 HIL_STATE_QUATERNION(HIL_STATE_QUATERNION_DATA),
34271 #[doc = "Contains the home position. \tThe home position is the default position that the system will return to and land on. \tThe position must be set automatically by the system during the takeoff, and may also be explicitly set using MAV_CMD_DO_SET_HOME. \tThe global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. \tUnder normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. \tThe approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. Note: this message can be requested by sending the MAV_CMD_REQUEST_MESSAGE with param1=242 (or the deprecated MAV_CMD_GET_HOME_POSITION command)."]
34272 #[doc = ""]
34273 #[doc = "ID: 242"]
34274 HOME_POSITION(HOME_POSITION_DATA),
34275 #[doc = "Temperature and humidity from hygrometer."]
34276 #[doc = ""]
34277 #[doc = "ID: 12920"]
34278 HYGROMETER_SENSOR(HYGROMETER_SENSOR_DATA),
34279 #[doc = "Illuminator status."]
34280 #[doc = ""]
34281 #[doc = "ID: 440"]
34282 ILLUMINATOR_STATUS(ILLUMINATOR_STATUS_DATA),
34283 #[doc = "Status of the Iridium SBD link."]
34284 #[doc = ""]
34285 #[doc = "ID: 335"]
34286 ISBD_LINK_STATUS(ISBD_LINK_STATUS_DATA),
34287 #[doc = "The location of a landing target. See: <https://mavlink.io/en/services/landing_target.html>."]
34288 #[doc = ""]
34289 #[doc = "ID: 149"]
34290 LANDING_TARGET(LANDING_TARGET_DATA),
34291 #[doc = "Status generated in each node in the communication chain and injected into MAVLink stream."]
34292 #[doc = ""]
34293 #[doc = "ID: 8"]
34294 LINK_NODE_STATUS(LINK_NODE_STATUS_DATA),
34295 #[doc = "The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)."]
34296 #[doc = ""]
34297 #[doc = "ID: 32"]
34298 LOCAL_POSITION_NED(LOCAL_POSITION_NED_DATA),
34299 #[doc = "The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)."]
34300 #[doc = ""]
34301 #[doc = "ID: 64"]
34302 LOCAL_POSITION_NED_COV(LOCAL_POSITION_NED_COV_DATA),
34303 #[doc = "The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)."]
34304 #[doc = ""]
34305 #[doc = "ID: 89"]
34306 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA),
34307 #[doc = "An ack for a LOGGING_DATA_ACKED message."]
34308 #[doc = ""]
34309 #[doc = "ID: 268"]
34310 LOGGING_ACK(LOGGING_ACK_DATA),
34311 #[doc = "A message containing logged data (see also MAV_CMD_LOGGING_START)."]
34312 #[doc = ""]
34313 #[doc = "ID: 266"]
34314 LOGGING_DATA(LOGGING_DATA_DATA),
34315 #[doc = "A message containing logged data which requires a LOGGING_ACK to be sent back."]
34316 #[doc = ""]
34317 #[doc = "ID: 267"]
34318 LOGGING_DATA_ACKED(LOGGING_DATA_ACKED_DATA),
34319 #[doc = "Reply to LOG_REQUEST_DATA."]
34320 #[doc = ""]
34321 #[doc = "ID: 120"]
34322 LOG_DATA(LOG_DATA_DATA),
34323 #[doc = "Reply to LOG_REQUEST_LIST."]
34324 #[doc = ""]
34325 #[doc = "ID: 118"]
34326 LOG_ENTRY(LOG_ENTRY_DATA),
34327 #[doc = "Erase all logs."]
34328 #[doc = ""]
34329 #[doc = "ID: 121"]
34330 LOG_ERASE(LOG_ERASE_DATA),
34331 #[doc = "Request a chunk of a log."]
34332 #[doc = ""]
34333 #[doc = "ID: 119"]
34334 LOG_REQUEST_DATA(LOG_REQUEST_DATA_DATA),
34335 #[doc = "Stop log transfer and resume normal logging."]
34336 #[doc = ""]
34337 #[doc = "ID: 122"]
34338 LOG_REQUEST_END(LOG_REQUEST_END_DATA),
34339 #[doc = "Request a list of available logs. On some systems calling this may stop on-board logging until LOG_REQUEST_END is called. If there are no log files available this request shall be answered with one LOG_ENTRY message with id = 0 and num_logs = 0."]
34340 #[doc = ""]
34341 #[doc = "ID: 117"]
34342 LOG_REQUEST_LIST(LOG_REQUEST_LIST_DATA),
34343 #[doc = "Reports results of completed compass calibration. Sent until MAG_CAL_ACK received."]
34344 #[doc = ""]
34345 #[doc = "ID: 192"]
34346 MAG_CAL_REPORT(MAG_CAL_REPORT_DATA),
34347 #[doc = "This message provides an API for manually controlling the vehicle using standard joystick axes nomenclature, along with a joystick-like input device. Unused axes can be disabled and buttons states are transmitted as individual on/off bits of a bitmask."]
34348 #[doc = ""]
34349 #[doc = "ID: 69"]
34350 MANUAL_CONTROL(MANUAL_CONTROL_DATA),
34351 #[doc = "Setpoint in roll, pitch, yaw and thrust from the operator."]
34352 #[doc = ""]
34353 #[doc = "ID: 81"]
34354 MANUAL_SETPOINT(MANUAL_SETPOINT_DATA),
34355 #[doc = "Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output."]
34356 #[doc = ""]
34357 #[doc = "ID: 249"]
34358 MEMORY_VECT(MEMORY_VECT_DATA),
34359 #[doc = "The interval between messages for a particular MAVLink message ID. This message is sent in response to the MAV_CMD_REQUEST_MESSAGE command with param1=244 (this message) and param2=message_id (the id of the message for which the interval is required). \tIt may also be sent in response to MAV_CMD_GET_MESSAGE_INTERVAL. \tThis interface replaces DATA_STREAM."]
34360 #[doc = ""]
34361 #[doc = "ID: 244"]
34362 MESSAGE_INTERVAL(MESSAGE_INTERVAL_DATA),
34363 #[doc = "Acknowledgment message during waypoint handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero)."]
34364 #[doc = ""]
34365 #[doc = "ID: 47"]
34366 MISSION_ACK(MISSION_ACK_DATA),
34367 #[doc = "Delete all mission items at once."]
34368 #[doc = ""]
34369 #[doc = "ID: 45"]
34370 MISSION_CLEAR_ALL(MISSION_CLEAR_ALL_DATA),
34371 #[doc = "This message is emitted as response to MISSION_REQUEST_LIST by the MAV and to initiate a write transaction. The GCS can then request the individual mission item based on the knowledge of the total number of waypoints."]
34372 #[doc = ""]
34373 #[doc = "ID: 44"]
34374 MISSION_COUNT(MISSION_COUNT_DATA),
34375 #[doc = "Message that announces the sequence number of the current target mission item (that the system will fly towards/execute when the mission is running). This message should be streamed all the time (nominally at 1Hz). This message should be emitted following a call to MAV_CMD_DO_SET_MISSION_CURRENT or MISSION_SET_CURRENT."]
34376 #[doc = ""]
34377 #[doc = "ID: 42"]
34378 MISSION_CURRENT(MISSION_CURRENT_DATA),
34379 #[doc = "Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN may be used to indicate an optional/default value (e.g. to use the system's current latitude or yaw rather than a specific value). See also <https://mavlink.io/en/services/mission.html>."]
34380 #[doc = ""]
34381 #[doc = "ID: 39"]
34382 #[deprecated = " See `MISSION_ITEM_INT` (Deprecated since 2020-06)"]
34383 MISSION_ITEM(MISSION_ITEM_DATA),
34384 #[doc = "Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). See also <https://mavlink.io/en/services/mission.html>."]
34385 #[doc = ""]
34386 #[doc = "ID: 73"]
34387 MISSION_ITEM_INT(MISSION_ITEM_INT_DATA),
34388 #[doc = "A certain mission item has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next waypoint."]
34389 #[doc = ""]
34390 #[doc = "ID: 46"]
34391 MISSION_ITEM_REACHED(MISSION_ITEM_REACHED_DATA),
34392 #[doc = "Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. <https://mavlink.io/en/services/mission.html>."]
34393 #[doc = ""]
34394 #[doc = "ID: 40"]
34395 #[deprecated = "A system that gets this request should respond with MISSION_ITEM_INT (as though MISSION_REQUEST_INT was received). See `MISSION_REQUEST_INT` (Deprecated since 2020-06)"]
34396 MISSION_REQUEST(MISSION_REQUEST_DATA),
34397 #[doc = "Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM_INT message. <https://mavlink.io/en/services/mission.html>."]
34398 #[doc = ""]
34399 #[doc = "ID: 51"]
34400 MISSION_REQUEST_INT(MISSION_REQUEST_INT_DATA),
34401 #[doc = "Request the overall list of mission items from the system/component."]
34402 #[doc = ""]
34403 #[doc = "ID: 43"]
34404 MISSION_REQUEST_LIST(MISSION_REQUEST_LIST_DATA),
34405 #[doc = "Request a partial list of mission items from the system/component. <https://mavlink.io/en/services/mission.html>. If start and end index are the same, just send one waypoint."]
34406 #[doc = ""]
34407 #[doc = "ID: 37"]
34408 MISSION_REQUEST_PARTIAL_LIST(MISSION_REQUEST_PARTIAL_LIST_DATA),
34409 #[doc = "Set the mission item with sequence number seq as the current item and emit MISSION_CURRENT (whether or not the mission number changed). If a mission is currently being executed, the system will continue to this new mission item on the shortest path, skipping any intermediate mission items. Note that mission jump repeat counters are not reset (see MAV_CMD_DO_JUMP param2). This message may trigger a mission state-machine change on some systems: for example from MISSION_STATE_NOT_STARTED or MISSION_STATE_PAUSED to MISSION_STATE_ACTIVE. If the system is in mission mode, on those systems this command might therefore start, restart or resume the mission. If the system is not in mission mode this message must not trigger a switch to mission mode."]
34410 #[doc = ""]
34411 #[doc = "ID: 41"]
34412 #[deprecated = " See `MAV_CMD_DO_SET_MISSION_CURRENT` (Deprecated since 2022-08)"]
34413 MISSION_SET_CURRENT(MISSION_SET_CURRENT_DATA),
34414 #[doc = "This message is sent to the MAV to write a partial list. If start index == end index, only one item will be transmitted / updated. If the start index is NOT 0 and above the current list size, this request should be REJECTED!."]
34415 #[doc = ""]
34416 #[doc = "ID: 38"]
34417 MISSION_WRITE_PARTIAL_LIST(MISSION_WRITE_PARTIAL_LIST_DATA),
34418 #[doc = "Orientation of a mount."]
34419 #[doc = ""]
34420 #[doc = "ID: 265"]
34421 #[deprecated = "This message is being superseded by MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW. The message can still be used to communicate with legacy gimbals implementing it. See `MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW` (Deprecated since 2020-01)"]
34422 MOUNT_ORIENTATION(MOUNT_ORIENTATION_DATA),
34423 #[doc = "Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output."]
34424 #[doc = ""]
34425 #[doc = "ID: 251"]
34426 NAMED_VALUE_FLOAT(NAMED_VALUE_FLOAT_DATA),
34427 #[doc = "Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output."]
34428 #[doc = ""]
34429 #[doc = "ID: 252"]
34430 NAMED_VALUE_INT(NAMED_VALUE_INT_DATA),
34431 #[doc = "The state of the navigation and position controller."]
34432 #[doc = ""]
34433 #[doc = "ID: 62"]
34434 NAV_CONTROLLER_OUTPUT(NAV_CONTROLLER_OUTPUT_DATA),
34435 #[doc = "Obstacle distances in front of the sensor, starting from the left in increment degrees to the right."]
34436 #[doc = ""]
34437 #[doc = "ID: 330"]
34438 OBSTACLE_DISTANCE(OBSTACLE_DISTANCE_DATA),
34439 #[doc = "Odometry message to communicate odometry information with an external interface. Fits ROS REP 147 standard for aerial vehicles (<http://www.ros.org/reps/rep-0147.html>)."]
34440 #[doc = ""]
34441 #[doc = "ID: 331"]
34442 ODOMETRY(ODOMETRY_DATA),
34443 #[doc = "Hardware status sent by an onboard computer."]
34444 #[doc = ""]
34445 #[doc = "ID: 390"]
34446 ONBOARD_COMPUTER_STATUS(ONBOARD_COMPUTER_STATUS_DATA),
34447 #[doc = "Transmitter (remote ID system) is enabled and ready to start sending location and other required information. This is streamed by transmitter. A flight controller uses it as a condition to arm."]
34448 #[doc = ""]
34449 #[doc = "ID: 12918"]
34450 OPEN_DRONE_ID_ARM_STATUS(OPEN_DRONE_ID_ARM_STATUS_DATA),
34451 #[doc = "Data for filling the OpenDroneID Authentication message. The Authentication Message defines a field that can provide a means of authenticity for the identity of the UAS (Unmanned Aircraft System). The Authentication message can have two different formats. For data page 0, the fields PageCount, Length and TimeStamp are present and AuthData is only 17 bytes. For data page 1 through 15, PageCount, Length and TimeStamp are not present and the size of AuthData is 23 bytes."]
34452 #[doc = ""]
34453 #[doc = "ID: 12902"]
34454 OPEN_DRONE_ID_AUTHENTICATION(OPEN_DRONE_ID_AUTHENTICATION_DATA),
34455 #[doc = "Data for filling the OpenDroneID Basic ID message. This and the below messages are primarily meant for feeding data to/from an OpenDroneID implementation. E.g. <https://github.com/opendroneid/opendroneid-core-c>. These messages are compatible with the ASTM F3411 Remote ID standard and the ASD-STAN prEN 4709-002 Direct Remote ID standard. Additional information and usage of these messages is documented at <https://mavlink.io/en/services/opendroneid.html>."]
34456 #[doc = ""]
34457 #[doc = "ID: 12900"]
34458 OPEN_DRONE_ID_BASIC_ID(OPEN_DRONE_ID_BASIC_ID_DATA),
34459 #[doc = "Data for filling the OpenDroneID Location message. The float data types are 32-bit IEEE 754. The Location message provides the location, altitude, direction and speed of the aircraft."]
34460 #[doc = ""]
34461 #[doc = "ID: 12901"]
34462 OPEN_DRONE_ID_LOCATION(OPEN_DRONE_ID_LOCATION_DATA),
34463 #[doc = "An OpenDroneID message pack is a container for multiple encoded OpenDroneID messages (i.e. not in the format given for the above message descriptions but after encoding into the compressed OpenDroneID byte format). Used e.g. when transmitting on Bluetooth 5.0 Long Range/Extended Advertising or on WiFi Neighbor Aware Networking or on WiFi Beacon."]
34464 #[doc = ""]
34465 #[doc = "ID: 12915"]
34466 OPEN_DRONE_ID_MESSAGE_PACK(OPEN_DRONE_ID_MESSAGE_PACK_DATA),
34467 #[doc = "Data for filling the OpenDroneID Operator ID message, which contains the CAA (Civil Aviation Authority) issued operator ID."]
34468 #[doc = ""]
34469 #[doc = "ID: 12905"]
34470 OPEN_DRONE_ID_OPERATOR_ID(OPEN_DRONE_ID_OPERATOR_ID_DATA),
34471 #[doc = "Data for filling the OpenDroneID Self ID message. The Self ID Message is an opportunity for the operator to (optionally) declare their identity and purpose of the flight. This message can provide additional information that could reduce the threat profile of a UA (Unmanned Aircraft) flying in a particular area or manner. This message can also be used to provide optional additional clarification in an emergency/remote ID system failure situation."]
34472 #[doc = ""]
34473 #[doc = "ID: 12903"]
34474 OPEN_DRONE_ID_SELF_ID(OPEN_DRONE_ID_SELF_ID_DATA),
34475 #[doc = "Data for filling the OpenDroneID System message. The System Message contains general system information including the operator location/altitude and possible aircraft group and/or category/class information."]
34476 #[doc = ""]
34477 #[doc = "ID: 12904"]
34478 OPEN_DRONE_ID_SYSTEM(OPEN_DRONE_ID_SYSTEM_DATA),
34479 #[doc = "Update the data in the OPEN_DRONE_ID_SYSTEM message with new location information. This can be sent to update the location information for the operator when no other information in the SYSTEM message has changed. This message allows for efficient operation on radio links which have limited uplink bandwidth while meeting requirements for update frequency of the operator location."]
34480 #[doc = ""]
34481 #[doc = "ID: 12919"]
34482 OPEN_DRONE_ID_SYSTEM_UPDATE(OPEN_DRONE_ID_SYSTEM_UPDATE_DATA),
34483 #[doc = "Optical flow from a flow sensor (e.g. optical mouse sensor)."]
34484 #[doc = ""]
34485 #[doc = "ID: 100"]
34486 OPTICAL_FLOW(OPTICAL_FLOW_DATA),
34487 #[doc = "Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse sensor)."]
34488 #[doc = ""]
34489 #[doc = "ID: 106"]
34490 OPTICAL_FLOW_RAD(OPTICAL_FLOW_RAD_DATA),
34491 #[doc = "Vehicle status report that is sent out while orbit execution is in progress (see MAV_CMD_DO_ORBIT)."]
34492 #[doc = ""]
34493 #[doc = "ID: 360"]
34494 ORBIT_EXECUTION_STATUS(ORBIT_EXECUTION_STATUS_DATA),
34495 #[doc = "Response from a PARAM_EXT_SET message."]
34496 #[doc = ""]
34497 #[doc = "ID: 324"]
34498 PARAM_EXT_ACK(PARAM_EXT_ACK_DATA),
34499 #[doc = "Request all parameters of this component. All parameters should be emitted in response as PARAM_EXT_VALUE."]
34500 #[doc = ""]
34501 #[doc = "ID: 321"]
34502 PARAM_EXT_REQUEST_LIST(PARAM_EXT_REQUEST_LIST_DATA),
34503 #[doc = "Request to read the value of a parameter with either the param_id string id or param_index. PARAM_EXT_VALUE should be emitted in response."]
34504 #[doc = ""]
34505 #[doc = "ID: 320"]
34506 PARAM_EXT_REQUEST_READ(PARAM_EXT_REQUEST_READ_DATA),
34507 #[doc = "Set a parameter value. In order to deal with message loss (and retransmission of PARAM_EXT_SET), when setting a parameter value and the new value is the same as the current value, you will immediately get a PARAM_ACK_ACCEPTED response. If the current state is PARAM_ACK_IN_PROGRESS, you will accordingly receive a PARAM_ACK_IN_PROGRESS in response."]
34508 #[doc = ""]
34509 #[doc = "ID: 323"]
34510 PARAM_EXT_SET(PARAM_EXT_SET_DATA),
34511 #[doc = "Emit the value of a parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows them to re-request missing parameters after a loss or timeout."]
34512 #[doc = ""]
34513 #[doc = "ID: 322"]
34514 PARAM_EXT_VALUE(PARAM_EXT_VALUE_DATA),
34515 #[doc = "Bind a RC channel to a parameter. The parameter should change according to the RC channel value."]
34516 #[doc = ""]
34517 #[doc = "ID: 50"]
34518 PARAM_MAP_RC(PARAM_MAP_RC_DATA),
34519 #[doc = "Request all parameters of this component. After this request, all parameters are emitted. The parameter microservice is documented at <https://mavlink.io/en/services/parameter.html>."]
34520 #[doc = ""]
34521 #[doc = "ID: 21"]
34522 PARAM_REQUEST_LIST(PARAM_REQUEST_LIST_DATA),
34523 #[doc = "Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] ->value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also <https://mavlink.io/en/services/parameter.html> for a full documentation of QGroundControl and IMU code."]
34524 #[doc = ""]
34525 #[doc = "ID: 20"]
34526 PARAM_REQUEST_READ(PARAM_REQUEST_READ_DATA),
34527 #[doc = "Set a parameter value (write new value to permanent storage). The receiving component should acknowledge the new parameter value by broadcasting a PARAM_VALUE message (broadcasting ensures that multiple GCS all have an up-to-date list of all parameters). If the sending GCS did not receive a PARAM_VALUE within its timeout time, it should re-send the PARAM_SET message. The parameter microservice is documented at <https://mavlink.io/en/services/parameter.html>."]
34528 #[doc = ""]
34529 #[doc = "ID: 23"]
34530 PARAM_SET(PARAM_SET_DATA),
34531 #[doc = "Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. The parameter microservice is documented at <https://mavlink.io/en/services/parameter.html>."]
34532 #[doc = ""]
34533 #[doc = "ID: 22"]
34534 PARAM_VALUE(PARAM_VALUE_DATA),
34535 #[doc = "A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. The ping microservice is documented at <https://mavlink.io/en/services/ping.html>."]
34536 #[doc = ""]
34537 #[doc = "ID: 4"]
34538 #[deprecated = "To be removed / merged with TIMESYNC. See `TIMESYNC` (Deprecated since 2011-08)"]
34539 PING(PING_DATA),
34540 #[doc = "Control vehicle tone generation (buzzer)."]
34541 #[doc = ""]
34542 #[doc = "ID: 258"]
34543 #[deprecated = "New version explicitly defines format. More interoperable. See `PLAY_TUNE_V2` (Deprecated since 2019-10)"]
34544 PLAY_TUNE(PLAY_TUNE_DATA),
34545 #[doc = "Play vehicle tone/tune (buzzer). Supersedes message PLAY_TUNE."]
34546 #[doc = ""]
34547 #[doc = "ID: 400"]
34548 PLAY_TUNE_V2(PLAY_TUNE_V2_DATA),
34549 #[doc = "Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being controlled this way."]
34550 #[doc = ""]
34551 #[doc = "ID: 87"]
34552 POSITION_TARGET_GLOBAL_INT(POSITION_TARGET_GLOBAL_INT_DATA),
34553 #[doc = "Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_LOCAL_NED if the vehicle is being controlled this way."]
34554 #[doc = ""]
34555 #[doc = "ID: 85"]
34556 POSITION_TARGET_LOCAL_NED(POSITION_TARGET_LOCAL_NED_DATA),
34557 #[doc = "Power supply status."]
34558 #[doc = ""]
34559 #[doc = "ID: 125"]
34560 POWER_STATUS(POWER_STATUS_DATA),
34561 #[doc = "Version and capability of protocol version. This message can be requested with MAV_CMD_REQUEST_MESSAGE and is used as part of the handshaking to establish which MAVLink version should be used on the network. Every node should respond to a request for PROTOCOL_VERSION to enable the handshaking. Library implementers should consider adding this into the default decoding state machine to allow the protocol core to respond directly."]
34562 #[doc = ""]
34563 #[doc = "ID: 300"]
34564 PROTOCOL_VERSION(PROTOCOL_VERSION_DATA),
34565 #[doc = "Status generated by radio and injected into MAVLink stream."]
34566 #[doc = ""]
34567 #[doc = "ID: 109"]
34568 RADIO_STATUS(RADIO_STATUS_DATA),
34569 #[doc = "The RAW IMU readings for a 9DOF sensor, which is identified by the id (default IMU1). This message should always contain the true raw values without any scaling to allow data capture and system debugging."]
34570 #[doc = ""]
34571 #[doc = "ID: 27"]
34572 RAW_IMU(RAW_IMU_DATA),
34573 #[doc = "The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values."]
34574 #[doc = ""]
34575 #[doc = "ID: 28"]
34576 RAW_PRESSURE(RAW_PRESSURE_DATA),
34577 #[doc = "RPM sensor data message."]
34578 #[doc = ""]
34579 #[doc = "ID: 339"]
34580 RAW_RPM(RAW_RPM_DATA),
34581 #[doc = "The PPM values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification."]
34582 #[doc = ""]
34583 #[doc = "ID: 65"]
34584 RC_CHANNELS(RC_CHANNELS_DATA),
34585 #[doc = "The RAW values of the RC channels sent to the MAV to override info received from the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. Note carefully the semantic differences between the first 8 channels and the subsequent channels."]
34586 #[doc = ""]
34587 #[doc = "ID: 70"]
34588 RC_CHANNELS_OVERRIDE(RC_CHANNELS_OVERRIDE_DATA),
34589 #[doc = "The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification."]
34590 #[doc = ""]
34591 #[doc = "ID: 35"]
34592 RC_CHANNELS_RAW(RC_CHANNELS_RAW_DATA),
34593 #[doc = "The scaled values of the RC channels received: (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to INT16_MAX."]
34594 #[doc = ""]
34595 #[doc = "ID: 34"]
34596 RC_CHANNELS_SCALED(RC_CHANNELS_SCALED_DATA),
34597 #[doc = "Request a data stream."]
34598 #[doc = ""]
34599 #[doc = "ID: 66"]
34600 #[deprecated = " See `MAV_CMD_SET_MESSAGE_INTERVAL ` (Deprecated since 2015-08)"]
34601 REQUEST_DATA_STREAM(REQUEST_DATA_STREAM_DATA),
34602 #[doc = "Request one or more events to be (re-)sent. If first_sequence==last_sequence, only a single event is requested. Note that first_sequence can be larger than last_sequence (because the sequence number can wrap). Each sequence will trigger an EVENT or EVENT_ERROR response."]
34603 #[doc = ""]
34604 #[doc = "ID: 412"]
34605 REQUEST_EVENT(REQUEST_EVENT_DATA),
34606 #[doc = "The autopilot is requesting a resource (file, binary, other type of data)."]
34607 #[doc = ""]
34608 #[doc = "ID: 142"]
34609 RESOURCE_REQUEST(RESOURCE_REQUEST_DATA),
34610 #[doc = "Response to a REQUEST_EVENT in case of an error (e.g. the event is not available anymore)."]
34611 #[doc = ""]
34612 #[doc = "ID: 413"]
34613 RESPONSE_EVENT_ERROR(RESPONSE_EVENT_ERROR_DATA),
34614 #[doc = "Read out the safety zone the MAV currently assumes."]
34615 #[doc = ""]
34616 #[doc = "ID: 55"]
34617 SAFETY_ALLOWED_AREA(SAFETY_ALLOWED_AREA_DATA),
34618 #[doc = "Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/waypoints to accept and which to reject. Safety areas are often enforced by national or competition regulations."]
34619 #[doc = ""]
34620 #[doc = "ID: 54"]
34621 SAFETY_SET_ALLOWED_AREA(SAFETY_SET_ALLOWED_AREA_DATA),
34622 #[doc = "The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units."]
34623 #[doc = ""]
34624 #[doc = "ID: 26"]
34625 SCALED_IMU(SCALED_IMU_DATA),
34626 #[doc = "The RAW IMU readings for secondary 9DOF sensor setup. This message should contain the scaled values to the described units."]
34627 #[doc = ""]
34628 #[doc = "ID: 116"]
34629 SCALED_IMU2(SCALED_IMU2_DATA),
34630 #[doc = "The RAW IMU readings for 3rd 9DOF sensor setup. This message should contain the scaled values to the described units."]
34631 #[doc = ""]
34632 #[doc = "ID: 129"]
34633 SCALED_IMU3(SCALED_IMU3_DATA),
34634 #[doc = "The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field."]
34635 #[doc = ""]
34636 #[doc = "ID: 29"]
34637 SCALED_PRESSURE(SCALED_PRESSURE_DATA),
34638 #[doc = "Barometer readings for 2nd barometer."]
34639 #[doc = ""]
34640 #[doc = "ID: 137"]
34641 SCALED_PRESSURE2(SCALED_PRESSURE2_DATA),
34642 #[doc = "Barometer readings for 3rd barometer."]
34643 #[doc = ""]
34644 #[doc = "ID: 143"]
34645 SCALED_PRESSURE3(SCALED_PRESSURE3_DATA),
34646 #[doc = "Control a serial port. This can be used for raw access to an onboard serial peripheral such as a GPS or telemetry radio. It is designed to make it possible to update the devices firmware via MAVLink messages or change the devices settings. A message with zero bytes can be used to change just the baudrate."]
34647 #[doc = ""]
34648 #[doc = "ID: 126"]
34649 SERIAL_CONTROL(SERIAL_CONTROL_DATA),
34650 #[doc = "Superseded by ACTUATOR_OUTPUT_STATUS. The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%."]
34651 #[doc = ""]
34652 #[doc = "ID: 36"]
34653 SERVO_OUTPUT_RAW(SERVO_OUTPUT_RAW_DATA),
34654 #[doc = "Setup a MAVLink2 signing key. If called with secret_key of all zero and zero initial_timestamp will disable signing."]
34655 #[doc = ""]
34656 #[doc = "ID: 256"]
34657 SETUP_SIGNING(SETUP_SIGNING_DATA),
34658 #[doc = "Set the vehicle attitude and body angular rates."]
34659 #[doc = ""]
34660 #[doc = "ID: 139"]
34661 SET_ACTUATOR_CONTROL_TARGET(SET_ACTUATOR_CONTROL_TARGET_DATA),
34662 #[doc = "Sets a desired vehicle attitude. Used by an external controller to command the vehicle (manual controller or other system)."]
34663 #[doc = ""]
34664 #[doc = "ID: 82"]
34665 SET_ATTITUDE_TARGET(SET_ATTITUDE_TARGET_DATA),
34666 #[doc = "Sets the GPS coordinates of the vehicle local origin (0,0,0) position. Vehicle should emit GPS_GLOBAL_ORIGIN irrespective of whether the origin is changed. This enables transform between the local coordinate frame and the global (GPS) coordinate frame, which may be necessary when (for example) indoor and outdoor settings are connected and the MAV should move from in- to outdoor."]
34667 #[doc = ""]
34668 #[doc = "ID: 48"]
34669 #[deprecated = " See `MAV_CMD_SET_GLOBAL_ORIGIN` (Deprecated since 2025-04)"]
34670 SET_GPS_GLOBAL_ORIGIN(SET_GPS_GLOBAL_ORIGIN_DATA),
34671 #[doc = "Sets the home position. \tThe home position is the default position that the system will return to and land on. The position is set automatically by the system during the takeoff (and may also be set using this message). The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242)."]
34672 #[doc = ""]
34673 #[doc = "ID: 243"]
34674 #[deprecated = "The command protocol version (MAV_CMD_DO_SET_HOME) allows a GCS to detect when setting the home position has failed. See `MAV_CMD_DO_SET_HOME` (Deprecated since 2022-02)"]
34675 SET_HOME_POSITION(SET_HOME_POSITION_DATA),
34676 #[doc = "Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component."]
34677 #[doc = ""]
34678 #[doc = "ID: 11"]
34679 #[deprecated = "Use COMMAND_LONG with MAV_CMD_DO_SET_MODE instead. See `MAV_CMD_DO_SET_MODE` (Deprecated since 2015-12)"]
34680 SET_MODE(SET_MODE_DATA),
34681 #[doc = "Sets a desired vehicle position, velocity, and/or acceleration in a global coordinate system (WGS84). Used by an external controller to command the vehicle (manual controller or other system)."]
34682 #[doc = ""]
34683 #[doc = "ID: 86"]
34684 SET_POSITION_TARGET_GLOBAL_INT(SET_POSITION_TARGET_GLOBAL_INT_DATA),
34685 #[doc = "Sets a desired vehicle position in a local north-east-down coordinate frame. Used by an external controller to command the vehicle (manual controller or other system)."]
34686 #[doc = ""]
34687 #[doc = "ID: 84"]
34688 SET_POSITION_TARGET_LOCAL_NED(SET_POSITION_TARGET_LOCAL_NED_DATA),
34689 #[doc = "Status of simulation environment, if used."]
34690 #[doc = ""]
34691 #[doc = "ID: 108"]
34692 SIM_STATE(SIM_STATE_DATA),
34693 #[doc = "Smart Battery information (static/infrequent update). Use for updates from: smart battery to flight stack, flight stack to GCS. Use BATTERY_STATUS for the frequent battery updates."]
34694 #[doc = ""]
34695 #[doc = "ID: 370"]
34696 #[deprecated = "The BATTERY_INFO message is better aligned with UAVCAN messages, and in any case is useful even if a battery is not \"smart\". See `BATTERY_INFO` (Deprecated since 2024-02)"]
34697 SMART_BATTERY_INFO(SMART_BATTERY_INFO_DATA),
34698 #[doc = "Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz)."]
34699 #[doc = ""]
34700 #[doc = "ID: 253"]
34701 STATUSTEXT(STATUSTEXT_DATA),
34702 #[doc = "Information about a storage medium. This message is sent in response to a request with MAV_CMD_REQUEST_MESSAGE and whenever the status of the storage changes (STORAGE_STATUS). Use MAV_CMD_REQUEST_MESSAGE.param2 to indicate the index/id of requested storage: 0 for all, 1 for first, 2 for second, etc."]
34703 #[doc = ""]
34704 #[doc = "ID: 261"]
34705 STORAGE_INFORMATION(STORAGE_INFORMATION_DATA),
34706 #[doc = "Tune formats supported by vehicle. This should be emitted as response to MAV_CMD_REQUEST_MESSAGE."]
34707 #[doc = ""]
34708 #[doc = "ID: 401"]
34709 SUPPORTED_TUNES(SUPPORTED_TUNES_DATA),
34710 #[doc = "The system time is the time of the master clock. This can be emitted by flight controllers, onboard computers, or other components in the MAVLink network. Components that are using a less reliable time source, such as a battery-backed real time clock, can choose to match their system clock to that of a SYSTEM_TYPE that indicates a more recent time. This allows more broadly accurate date stamping of logs, and so on. If precise time synchronization is needed then use TIMESYNC instead."]
34711 #[doc = ""]
34712 #[doc = "ID: 2"]
34713 SYSTEM_TIME(SYSTEM_TIME_DATA),
34714 #[doc = "The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows whether the system is currently active or not and if an emergency occurred. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occurred it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout."]
34715 #[doc = ""]
34716 #[doc = "ID: 1"]
34717 SYS_STATUS(SYS_STATUS_DATA),
34718 #[doc = "Request that the vehicle report terrain height at the given location (expected response is a TERRAIN_REPORT). Used by GCS to check if vehicle has all terrain data needed for a mission."]
34719 #[doc = ""]
34720 #[doc = "ID: 135"]
34721 TERRAIN_CHECK(TERRAIN_CHECK_DATA),
34722 #[doc = "Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST. See terrain protocol docs: <https://mavlink.io/en/services/terrain.html>."]
34723 #[doc = ""]
34724 #[doc = "ID: 134"]
34725 TERRAIN_DATA(TERRAIN_DATA_DATA),
34726 #[doc = "Streamed from drone to report progress of terrain map download (initiated by TERRAIN_REQUEST), or sent as a response to a TERRAIN_CHECK request. See terrain protocol docs: <https://mavlink.io/en/services/terrain.html>."]
34727 #[doc = ""]
34728 #[doc = "ID: 136"]
34729 TERRAIN_REPORT(TERRAIN_REPORT_DATA),
34730 #[doc = "Request for terrain data and terrain status. See terrain protocol docs: <https://mavlink.io/en/services/terrain.html>."]
34731 #[doc = ""]
34732 #[doc = "ID: 133"]
34733 TERRAIN_REQUEST(TERRAIN_REQUEST_DATA),
34734 #[doc = "Time synchronization message. The message is used for both timesync requests and responses. The request is sent with `ts1=syncing component timestamp` and `tc1=0`, and may be broadcast or targeted to a specific system/component. The response is sent with `ts1=syncing component timestamp` (mirror back unchanged), and `tc1=responding component timestamp`, with the `target_system` and `target_component` set to ids of the original request. Systems can determine if they are receiving a request or response based on the value of `tc`. If the response has `target_system==target_component==0` the remote system has not been updated to use the component IDs and cannot reliably timesync; the requestor may report an error. Timestamps are UNIX Epoch time or time since system boot in nanoseconds (the timestamp format can be inferred by checking for the magnitude of the number; generally it doesn't matter as only the offset is used). The message sequence is repeated numerous times with results being filtered/averaged to estimate the offset. See also: <https://mavlink.io/en/services/timesync.html>."]
34735 #[doc = ""]
34736 #[doc = "ID: 111"]
34737 TIMESYNC(TIMESYNC_DATA),
34738 #[doc = "Time/duration estimates for various events and actions given the current vehicle state and position."]
34739 #[doc = ""]
34740 #[doc = "ID: 380"]
34741 TIME_ESTIMATE_TO_TARGET(TIME_ESTIMATE_TO_TARGET_DATA),
34742 #[doc = "Describe a trajectory using an array of up-to 5 bezier control points in the local frame (MAV_FRAME_LOCAL_NED)."]
34743 #[doc = ""]
34744 #[doc = "ID: 333"]
34745 TRAJECTORY_REPRESENTATION_BEZIER(TRAJECTORY_REPRESENTATION_BEZIER_DATA),
34746 #[doc = "Describe a trajectory using an array of up-to 5 waypoints in the local frame (MAV_FRAME_LOCAL_NED)."]
34747 #[doc = ""]
34748 #[doc = "ID: 332"]
34749 TRAJECTORY_REPRESENTATION_WAYPOINTS(TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA),
34750 #[doc = "Message for transporting \"arbitrary\" variable-length data from one component to another (broadcast is not forbidden, but discouraged). The encoding of the data is usually extension specific, i.e. determined by the source, and is usually not documented as part of the MAVLink specification."]
34751 #[doc = ""]
34752 #[doc = "ID: 385"]
34753 TUNNEL(TUNNEL_DATA),
34754 #[doc = "General information describing a particular UAVCAN node. Please refer to the definition of the UAVCAN service \"uavcan.protocol.GetNodeInfo\" for the background information. This message should be emitted by the system whenever a new node appears online, or an existing node reboots. Additionally, it can be emitted upon request from the other end of the MAVLink channel (see MAV_CMD_UAVCAN_GET_NODE_INFO). It is also not prohibited to emit this message unconditionally at a low frequency. The UAVCAN specification is available at <http://uavcan.org>."]
34755 #[doc = ""]
34756 #[doc = "ID: 311"]
34757 UAVCAN_NODE_INFO(UAVCAN_NODE_INFO_DATA),
34758 #[doc = "General status information of an UAVCAN node. Please refer to the definition of the UAVCAN message \"uavcan.protocol.NodeStatus\" for the background information. The UAVCAN specification is available at <http://uavcan.org>."]
34759 #[doc = ""]
34760 #[doc = "ID: 310"]
34761 UAVCAN_NODE_STATUS(UAVCAN_NODE_STATUS_DATA),
34762 #[doc = "The global position resulting from GPS and sensor fusion."]
34763 #[doc = ""]
34764 #[doc = "ID: 340"]
34765 UTM_GLOBAL_POSITION(UTM_GLOBAL_POSITION_DATA),
34766 #[doc = "Message implementing parts of the V2 payload specs in V1 frames for transitional support."]
34767 #[doc = ""]
34768 #[doc = "ID: 248"]
34769 V2_EXTENSION(V2_EXTENSION_DATA),
34770 #[doc = "Metrics typically displayed on a HUD for fixed wing aircraft."]
34771 #[doc = ""]
34772 #[doc = "ID: 74"]
34773 VFR_HUD(VFR_HUD_DATA),
34774 #[doc = "Vibration levels and accelerometer clipping."]
34775 #[doc = ""]
34776 #[doc = "ID: 241"]
34777 VIBRATION(VIBRATION_DATA),
34778 #[doc = "Global position estimate from a Vicon motion system source."]
34779 #[doc = ""]
34780 #[doc = "ID: 104"]
34781 VICON_POSITION_ESTIMATE(VICON_POSITION_ESTIMATE_DATA),
34782 #[doc = "Information about video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE, where param2 indicates the video stream id: 0 for all streams, 1 for first, 2 for second, etc."]
34783 #[doc = ""]
34784 #[doc = "ID: 269"]
34785 VIDEO_STREAM_INFORMATION(VIDEO_STREAM_INFORMATION_DATA),
34786 #[doc = "Information about the status of a video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE."]
34787 #[doc = ""]
34788 #[doc = "ID: 270"]
34789 VIDEO_STREAM_STATUS(VIDEO_STREAM_STATUS_DATA),
34790 #[doc = "Local position/attitude estimate from a vision source."]
34791 #[doc = ""]
34792 #[doc = "ID: 102"]
34793 VISION_POSITION_ESTIMATE(VISION_POSITION_ESTIMATE_DATA),
34794 #[doc = "Speed estimate from a vision source."]
34795 #[doc = ""]
34796 #[doc = "ID: 103"]
34797 VISION_SPEED_ESTIMATE(VISION_SPEED_ESTIMATE_DATA),
34798 #[doc = "Cumulative distance traveled for each reported wheel."]
34799 #[doc = ""]
34800 #[doc = "ID: 9000"]
34801 WHEEL_DISTANCE(WHEEL_DISTANCE_DATA),
34802 #[doc = "Configure WiFi AP SSID, password, and mode. This message is re-emitted as an acknowledgement by the AP. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE."]
34803 #[doc = ""]
34804 #[doc = "ID: 299"]
34805 WIFI_CONFIG_AP(WIFI_CONFIG_AP_DATA),
34806 #[doc = "Winch status."]
34807 #[doc = ""]
34808 #[doc = "ID: 9005"]
34809 WINCH_STATUS(WINCH_STATUS_DATA),
34810 #[doc = "Wind estimate from vehicle. Note that despite the name, this message does not actually contain any covariances but instead variability and accuracy fields in terms of standard deviation (1-STD)."]
34811 #[doc = ""]
34812 #[doc = "ID: 231"]
34813 WIND_COV(WIND_COV_DATA),
34814}
34815impl MavMessage {
34816 pub const fn all_ids() -> &'static [u32] {
34817 &[
34818 0u32, 1u32, 2u32, 4u32, 5u32, 6u32, 7u32, 8u32, 11u32, 20u32, 21u32, 22u32, 23u32,
34819 24u32, 25u32, 26u32, 27u32, 28u32, 29u32, 30u32, 31u32, 32u32, 33u32, 34u32, 35u32,
34820 36u32, 37u32, 38u32, 39u32, 40u32, 41u32, 42u32, 43u32, 44u32, 45u32, 46u32, 47u32,
34821 48u32, 49u32, 50u32, 51u32, 54u32, 55u32, 61u32, 62u32, 63u32, 64u32, 65u32, 66u32,
34822 67u32, 69u32, 70u32, 73u32, 74u32, 75u32, 76u32, 77u32, 80u32, 81u32, 82u32, 83u32,
34823 84u32, 85u32, 86u32, 87u32, 89u32, 90u32, 91u32, 92u32, 93u32, 100u32, 101u32, 102u32,
34824 103u32, 104u32, 105u32, 106u32, 107u32, 108u32, 109u32, 110u32, 111u32, 112u32, 113u32,
34825 114u32, 115u32, 116u32, 117u32, 118u32, 119u32, 120u32, 121u32, 122u32, 123u32, 124u32,
34826 125u32, 126u32, 127u32, 128u32, 129u32, 130u32, 131u32, 132u32, 133u32, 134u32, 135u32,
34827 136u32, 137u32, 138u32, 139u32, 140u32, 141u32, 142u32, 143u32, 144u32, 146u32, 147u32,
34828 148u32, 149u32, 162u32, 192u32, 225u32, 230u32, 231u32, 232u32, 233u32, 234u32, 235u32,
34829 241u32, 242u32, 243u32, 244u32, 245u32, 246u32, 247u32, 248u32, 249u32, 250u32, 251u32,
34830 252u32, 253u32, 254u32, 256u32, 257u32, 258u32, 259u32, 260u32, 261u32, 262u32, 263u32,
34831 264u32, 265u32, 266u32, 267u32, 268u32, 269u32, 270u32, 271u32, 275u32, 276u32, 277u32,
34832 280u32, 281u32, 282u32, 283u32, 284u32, 285u32, 286u32, 287u32, 288u32, 290u32, 291u32,
34833 299u32, 300u32, 301u32, 310u32, 311u32, 320u32, 321u32, 322u32, 323u32, 324u32, 330u32,
34834 331u32, 332u32, 333u32, 334u32, 335u32, 336u32, 339u32, 340u32, 350u32, 360u32, 370u32,
34835 371u32, 372u32, 373u32, 375u32, 380u32, 385u32, 386u32, 387u32, 388u32, 390u32, 395u32,
34836 396u32, 397u32, 400u32, 401u32, 410u32, 411u32, 412u32, 413u32, 435u32, 436u32, 437u32,
34837 440u32, 9000u32, 9005u32, 12900u32, 12901u32, 12902u32, 12903u32, 12904u32, 12905u32,
34838 12915u32, 12918u32, 12919u32, 12920u32,
34839 ]
34840 }
34841 pub const fn all_messages() -> &'static [(&'static str, u32)] {
34842 &[
34843 (HEARTBEAT_DATA::NAME, HEARTBEAT_DATA::ID),
34844 (SYS_STATUS_DATA::NAME, SYS_STATUS_DATA::ID),
34845 (SYSTEM_TIME_DATA::NAME, SYSTEM_TIME_DATA::ID),
34846 (PING_DATA::NAME, PING_DATA::ID),
34847 (
34848 CHANGE_OPERATOR_CONTROL_DATA::NAME,
34849 CHANGE_OPERATOR_CONTROL_DATA::ID,
34850 ),
34851 (
34852 CHANGE_OPERATOR_CONTROL_ACK_DATA::NAME,
34853 CHANGE_OPERATOR_CONTROL_ACK_DATA::ID,
34854 ),
34855 (AUTH_KEY_DATA::NAME, AUTH_KEY_DATA::ID),
34856 (LINK_NODE_STATUS_DATA::NAME, LINK_NODE_STATUS_DATA::ID),
34857 (SET_MODE_DATA::NAME, SET_MODE_DATA::ID),
34858 (PARAM_REQUEST_READ_DATA::NAME, PARAM_REQUEST_READ_DATA::ID),
34859 (PARAM_REQUEST_LIST_DATA::NAME, PARAM_REQUEST_LIST_DATA::ID),
34860 (PARAM_VALUE_DATA::NAME, PARAM_VALUE_DATA::ID),
34861 (PARAM_SET_DATA::NAME, PARAM_SET_DATA::ID),
34862 (GPS_RAW_INT_DATA::NAME, GPS_RAW_INT_DATA::ID),
34863 (GPS_STATUS_DATA::NAME, GPS_STATUS_DATA::ID),
34864 (SCALED_IMU_DATA::NAME, SCALED_IMU_DATA::ID),
34865 (RAW_IMU_DATA::NAME, RAW_IMU_DATA::ID),
34866 (RAW_PRESSURE_DATA::NAME, RAW_PRESSURE_DATA::ID),
34867 (SCALED_PRESSURE_DATA::NAME, SCALED_PRESSURE_DATA::ID),
34868 (ATTITUDE_DATA::NAME, ATTITUDE_DATA::ID),
34869 (ATTITUDE_QUATERNION_DATA::NAME, ATTITUDE_QUATERNION_DATA::ID),
34870 (LOCAL_POSITION_NED_DATA::NAME, LOCAL_POSITION_NED_DATA::ID),
34871 (GLOBAL_POSITION_INT_DATA::NAME, GLOBAL_POSITION_INT_DATA::ID),
34872 (RC_CHANNELS_SCALED_DATA::NAME, RC_CHANNELS_SCALED_DATA::ID),
34873 (RC_CHANNELS_RAW_DATA::NAME, RC_CHANNELS_RAW_DATA::ID),
34874 (SERVO_OUTPUT_RAW_DATA::NAME, SERVO_OUTPUT_RAW_DATA::ID),
34875 (
34876 MISSION_REQUEST_PARTIAL_LIST_DATA::NAME,
34877 MISSION_REQUEST_PARTIAL_LIST_DATA::ID,
34878 ),
34879 (
34880 MISSION_WRITE_PARTIAL_LIST_DATA::NAME,
34881 MISSION_WRITE_PARTIAL_LIST_DATA::ID,
34882 ),
34883 (MISSION_ITEM_DATA::NAME, MISSION_ITEM_DATA::ID),
34884 (MISSION_REQUEST_DATA::NAME, MISSION_REQUEST_DATA::ID),
34885 (MISSION_SET_CURRENT_DATA::NAME, MISSION_SET_CURRENT_DATA::ID),
34886 (MISSION_CURRENT_DATA::NAME, MISSION_CURRENT_DATA::ID),
34887 (
34888 MISSION_REQUEST_LIST_DATA::NAME,
34889 MISSION_REQUEST_LIST_DATA::ID,
34890 ),
34891 (MISSION_COUNT_DATA::NAME, MISSION_COUNT_DATA::ID),
34892 (MISSION_CLEAR_ALL_DATA::NAME, MISSION_CLEAR_ALL_DATA::ID),
34893 (
34894 MISSION_ITEM_REACHED_DATA::NAME,
34895 MISSION_ITEM_REACHED_DATA::ID,
34896 ),
34897 (MISSION_ACK_DATA::NAME, MISSION_ACK_DATA::ID),
34898 (
34899 SET_GPS_GLOBAL_ORIGIN_DATA::NAME,
34900 SET_GPS_GLOBAL_ORIGIN_DATA::ID,
34901 ),
34902 (GPS_GLOBAL_ORIGIN_DATA::NAME, GPS_GLOBAL_ORIGIN_DATA::ID),
34903 (PARAM_MAP_RC_DATA::NAME, PARAM_MAP_RC_DATA::ID),
34904 (MISSION_REQUEST_INT_DATA::NAME, MISSION_REQUEST_INT_DATA::ID),
34905 (
34906 SAFETY_SET_ALLOWED_AREA_DATA::NAME,
34907 SAFETY_SET_ALLOWED_AREA_DATA::ID,
34908 ),
34909 (SAFETY_ALLOWED_AREA_DATA::NAME, SAFETY_ALLOWED_AREA_DATA::ID),
34910 (
34911 ATTITUDE_QUATERNION_COV_DATA::NAME,
34912 ATTITUDE_QUATERNION_COV_DATA::ID,
34913 ),
34914 (
34915 NAV_CONTROLLER_OUTPUT_DATA::NAME,
34916 NAV_CONTROLLER_OUTPUT_DATA::ID,
34917 ),
34918 (
34919 GLOBAL_POSITION_INT_COV_DATA::NAME,
34920 GLOBAL_POSITION_INT_COV_DATA::ID,
34921 ),
34922 (
34923 LOCAL_POSITION_NED_COV_DATA::NAME,
34924 LOCAL_POSITION_NED_COV_DATA::ID,
34925 ),
34926 (RC_CHANNELS_DATA::NAME, RC_CHANNELS_DATA::ID),
34927 (REQUEST_DATA_STREAM_DATA::NAME, REQUEST_DATA_STREAM_DATA::ID),
34928 (DATA_STREAM_DATA::NAME, DATA_STREAM_DATA::ID),
34929 (MANUAL_CONTROL_DATA::NAME, MANUAL_CONTROL_DATA::ID),
34930 (
34931 RC_CHANNELS_OVERRIDE_DATA::NAME,
34932 RC_CHANNELS_OVERRIDE_DATA::ID,
34933 ),
34934 (MISSION_ITEM_INT_DATA::NAME, MISSION_ITEM_INT_DATA::ID),
34935 (VFR_HUD_DATA::NAME, VFR_HUD_DATA::ID),
34936 (COMMAND_INT_DATA::NAME, COMMAND_INT_DATA::ID),
34937 (COMMAND_LONG_DATA::NAME, COMMAND_LONG_DATA::ID),
34938 (COMMAND_ACK_DATA::NAME, COMMAND_ACK_DATA::ID),
34939 (COMMAND_CANCEL_DATA::NAME, COMMAND_CANCEL_DATA::ID),
34940 (MANUAL_SETPOINT_DATA::NAME, MANUAL_SETPOINT_DATA::ID),
34941 (SET_ATTITUDE_TARGET_DATA::NAME, SET_ATTITUDE_TARGET_DATA::ID),
34942 (ATTITUDE_TARGET_DATA::NAME, ATTITUDE_TARGET_DATA::ID),
34943 (
34944 SET_POSITION_TARGET_LOCAL_NED_DATA::NAME,
34945 SET_POSITION_TARGET_LOCAL_NED_DATA::ID,
34946 ),
34947 (
34948 POSITION_TARGET_LOCAL_NED_DATA::NAME,
34949 POSITION_TARGET_LOCAL_NED_DATA::ID,
34950 ),
34951 (
34952 SET_POSITION_TARGET_GLOBAL_INT_DATA::NAME,
34953 SET_POSITION_TARGET_GLOBAL_INT_DATA::ID,
34954 ),
34955 (
34956 POSITION_TARGET_GLOBAL_INT_DATA::NAME,
34957 POSITION_TARGET_GLOBAL_INT_DATA::ID,
34958 ),
34959 (
34960 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::NAME,
34961 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID,
34962 ),
34963 (HIL_STATE_DATA::NAME, HIL_STATE_DATA::ID),
34964 (HIL_CONTROLS_DATA::NAME, HIL_CONTROLS_DATA::ID),
34965 (HIL_RC_INPUTS_RAW_DATA::NAME, HIL_RC_INPUTS_RAW_DATA::ID),
34966 (
34967 HIL_ACTUATOR_CONTROLS_DATA::NAME,
34968 HIL_ACTUATOR_CONTROLS_DATA::ID,
34969 ),
34970 (OPTICAL_FLOW_DATA::NAME, OPTICAL_FLOW_DATA::ID),
34971 (
34972 GLOBAL_VISION_POSITION_ESTIMATE_DATA::NAME,
34973 GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID,
34974 ),
34975 (
34976 VISION_POSITION_ESTIMATE_DATA::NAME,
34977 VISION_POSITION_ESTIMATE_DATA::ID,
34978 ),
34979 (
34980 VISION_SPEED_ESTIMATE_DATA::NAME,
34981 VISION_SPEED_ESTIMATE_DATA::ID,
34982 ),
34983 (
34984 VICON_POSITION_ESTIMATE_DATA::NAME,
34985 VICON_POSITION_ESTIMATE_DATA::ID,
34986 ),
34987 (HIGHRES_IMU_DATA::NAME, HIGHRES_IMU_DATA::ID),
34988 (OPTICAL_FLOW_RAD_DATA::NAME, OPTICAL_FLOW_RAD_DATA::ID),
34989 (HIL_SENSOR_DATA::NAME, HIL_SENSOR_DATA::ID),
34990 (SIM_STATE_DATA::NAME, SIM_STATE_DATA::ID),
34991 (RADIO_STATUS_DATA::NAME, RADIO_STATUS_DATA::ID),
34992 (
34993 FILE_TRANSFER_PROTOCOL_DATA::NAME,
34994 FILE_TRANSFER_PROTOCOL_DATA::ID,
34995 ),
34996 (TIMESYNC_DATA::NAME, TIMESYNC_DATA::ID),
34997 (CAMERA_TRIGGER_DATA::NAME, CAMERA_TRIGGER_DATA::ID),
34998 (HIL_GPS_DATA::NAME, HIL_GPS_DATA::ID),
34999 (HIL_OPTICAL_FLOW_DATA::NAME, HIL_OPTICAL_FLOW_DATA::ID),
35000 (
35001 HIL_STATE_QUATERNION_DATA::NAME,
35002 HIL_STATE_QUATERNION_DATA::ID,
35003 ),
35004 (SCALED_IMU2_DATA::NAME, SCALED_IMU2_DATA::ID),
35005 (LOG_REQUEST_LIST_DATA::NAME, LOG_REQUEST_LIST_DATA::ID),
35006 (LOG_ENTRY_DATA::NAME, LOG_ENTRY_DATA::ID),
35007 (LOG_REQUEST_DATA_DATA::NAME, LOG_REQUEST_DATA_DATA::ID),
35008 (LOG_DATA_DATA::NAME, LOG_DATA_DATA::ID),
35009 (LOG_ERASE_DATA::NAME, LOG_ERASE_DATA::ID),
35010 (LOG_REQUEST_END_DATA::NAME, LOG_REQUEST_END_DATA::ID),
35011 (GPS_INJECT_DATA_DATA::NAME, GPS_INJECT_DATA_DATA::ID),
35012 (GPS2_RAW_DATA::NAME, GPS2_RAW_DATA::ID),
35013 (POWER_STATUS_DATA::NAME, POWER_STATUS_DATA::ID),
35014 (SERIAL_CONTROL_DATA::NAME, SERIAL_CONTROL_DATA::ID),
35015 (GPS_RTK_DATA::NAME, GPS_RTK_DATA::ID),
35016 (GPS2_RTK_DATA::NAME, GPS2_RTK_DATA::ID),
35017 (SCALED_IMU3_DATA::NAME, SCALED_IMU3_DATA::ID),
35018 (
35019 DATA_TRANSMISSION_HANDSHAKE_DATA::NAME,
35020 DATA_TRANSMISSION_HANDSHAKE_DATA::ID,
35021 ),
35022 (ENCAPSULATED_DATA_DATA::NAME, ENCAPSULATED_DATA_DATA::ID),
35023 (DISTANCE_SENSOR_DATA::NAME, DISTANCE_SENSOR_DATA::ID),
35024 (TERRAIN_REQUEST_DATA::NAME, TERRAIN_REQUEST_DATA::ID),
35025 (TERRAIN_DATA_DATA::NAME, TERRAIN_DATA_DATA::ID),
35026 (TERRAIN_CHECK_DATA::NAME, TERRAIN_CHECK_DATA::ID),
35027 (TERRAIN_REPORT_DATA::NAME, TERRAIN_REPORT_DATA::ID),
35028 (SCALED_PRESSURE2_DATA::NAME, SCALED_PRESSURE2_DATA::ID),
35029 (ATT_POS_MOCAP_DATA::NAME, ATT_POS_MOCAP_DATA::ID),
35030 (
35031 SET_ACTUATOR_CONTROL_TARGET_DATA::NAME,
35032 SET_ACTUATOR_CONTROL_TARGET_DATA::ID,
35033 ),
35034 (
35035 ACTUATOR_CONTROL_TARGET_DATA::NAME,
35036 ACTUATOR_CONTROL_TARGET_DATA::ID,
35037 ),
35038 (ALTITUDE_DATA::NAME, ALTITUDE_DATA::ID),
35039 (RESOURCE_REQUEST_DATA::NAME, RESOURCE_REQUEST_DATA::ID),
35040 (SCALED_PRESSURE3_DATA::NAME, SCALED_PRESSURE3_DATA::ID),
35041 (FOLLOW_TARGET_DATA::NAME, FOLLOW_TARGET_DATA::ID),
35042 (
35043 CONTROL_SYSTEM_STATE_DATA::NAME,
35044 CONTROL_SYSTEM_STATE_DATA::ID,
35045 ),
35046 (BATTERY_STATUS_DATA::NAME, BATTERY_STATUS_DATA::ID),
35047 (AUTOPILOT_VERSION_DATA::NAME, AUTOPILOT_VERSION_DATA::ID),
35048 (LANDING_TARGET_DATA::NAME, LANDING_TARGET_DATA::ID),
35049 (FENCE_STATUS_DATA::NAME, FENCE_STATUS_DATA::ID),
35050 (MAG_CAL_REPORT_DATA::NAME, MAG_CAL_REPORT_DATA::ID),
35051 (EFI_STATUS_DATA::NAME, EFI_STATUS_DATA::ID),
35052 (ESTIMATOR_STATUS_DATA::NAME, ESTIMATOR_STATUS_DATA::ID),
35053 (WIND_COV_DATA::NAME, WIND_COV_DATA::ID),
35054 (GPS_INPUT_DATA::NAME, GPS_INPUT_DATA::ID),
35055 (GPS_RTCM_DATA_DATA::NAME, GPS_RTCM_DATA_DATA::ID),
35056 (HIGH_LATENCY_DATA::NAME, HIGH_LATENCY_DATA::ID),
35057 (HIGH_LATENCY2_DATA::NAME, HIGH_LATENCY2_DATA::ID),
35058 (VIBRATION_DATA::NAME, VIBRATION_DATA::ID),
35059 (HOME_POSITION_DATA::NAME, HOME_POSITION_DATA::ID),
35060 (SET_HOME_POSITION_DATA::NAME, SET_HOME_POSITION_DATA::ID),
35061 (MESSAGE_INTERVAL_DATA::NAME, MESSAGE_INTERVAL_DATA::ID),
35062 (EXTENDED_SYS_STATE_DATA::NAME, EXTENDED_SYS_STATE_DATA::ID),
35063 (ADSB_VEHICLE_DATA::NAME, ADSB_VEHICLE_DATA::ID),
35064 (COLLISION_DATA::NAME, COLLISION_DATA::ID),
35065 (V2_EXTENSION_DATA::NAME, V2_EXTENSION_DATA::ID),
35066 (MEMORY_VECT_DATA::NAME, MEMORY_VECT_DATA::ID),
35067 (DEBUG_VECT_DATA::NAME, DEBUG_VECT_DATA::ID),
35068 (NAMED_VALUE_FLOAT_DATA::NAME, NAMED_VALUE_FLOAT_DATA::ID),
35069 (NAMED_VALUE_INT_DATA::NAME, NAMED_VALUE_INT_DATA::ID),
35070 (STATUSTEXT_DATA::NAME, STATUSTEXT_DATA::ID),
35071 (DEBUG_DATA::NAME, DEBUG_DATA::ID),
35072 (SETUP_SIGNING_DATA::NAME, SETUP_SIGNING_DATA::ID),
35073 (BUTTON_CHANGE_DATA::NAME, BUTTON_CHANGE_DATA::ID),
35074 (PLAY_TUNE_DATA::NAME, PLAY_TUNE_DATA::ID),
35075 (CAMERA_INFORMATION_DATA::NAME, CAMERA_INFORMATION_DATA::ID),
35076 (CAMERA_SETTINGS_DATA::NAME, CAMERA_SETTINGS_DATA::ID),
35077 (STORAGE_INFORMATION_DATA::NAME, STORAGE_INFORMATION_DATA::ID),
35078 (
35079 CAMERA_CAPTURE_STATUS_DATA::NAME,
35080 CAMERA_CAPTURE_STATUS_DATA::ID,
35081 ),
35082 (
35083 CAMERA_IMAGE_CAPTURED_DATA::NAME,
35084 CAMERA_IMAGE_CAPTURED_DATA::ID,
35085 ),
35086 (FLIGHT_INFORMATION_DATA::NAME, FLIGHT_INFORMATION_DATA::ID),
35087 (MOUNT_ORIENTATION_DATA::NAME, MOUNT_ORIENTATION_DATA::ID),
35088 (LOGGING_DATA_DATA::NAME, LOGGING_DATA_DATA::ID),
35089 (LOGGING_DATA_ACKED_DATA::NAME, LOGGING_DATA_ACKED_DATA::ID),
35090 (LOGGING_ACK_DATA::NAME, LOGGING_ACK_DATA::ID),
35091 (
35092 VIDEO_STREAM_INFORMATION_DATA::NAME,
35093 VIDEO_STREAM_INFORMATION_DATA::ID,
35094 ),
35095 (VIDEO_STREAM_STATUS_DATA::NAME, VIDEO_STREAM_STATUS_DATA::ID),
35096 (CAMERA_FOV_STATUS_DATA::NAME, CAMERA_FOV_STATUS_DATA::ID),
35097 (
35098 CAMERA_TRACKING_IMAGE_STATUS_DATA::NAME,
35099 CAMERA_TRACKING_IMAGE_STATUS_DATA::ID,
35100 ),
35101 (
35102 CAMERA_TRACKING_GEO_STATUS_DATA::NAME,
35103 CAMERA_TRACKING_GEO_STATUS_DATA::ID,
35104 ),
35105 (
35106 CAMERA_THERMAL_RANGE_DATA::NAME,
35107 CAMERA_THERMAL_RANGE_DATA::ID,
35108 ),
35109 (
35110 GIMBAL_MANAGER_INFORMATION_DATA::NAME,
35111 GIMBAL_MANAGER_INFORMATION_DATA::ID,
35112 ),
35113 (
35114 GIMBAL_MANAGER_STATUS_DATA::NAME,
35115 GIMBAL_MANAGER_STATUS_DATA::ID,
35116 ),
35117 (
35118 GIMBAL_MANAGER_SET_ATTITUDE_DATA::NAME,
35119 GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID,
35120 ),
35121 (
35122 GIMBAL_DEVICE_INFORMATION_DATA::NAME,
35123 GIMBAL_DEVICE_INFORMATION_DATA::ID,
35124 ),
35125 (
35126 GIMBAL_DEVICE_SET_ATTITUDE_DATA::NAME,
35127 GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID,
35128 ),
35129 (
35130 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::NAME,
35131 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID,
35132 ),
35133 (
35134 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::NAME,
35135 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID,
35136 ),
35137 (
35138 GIMBAL_MANAGER_SET_PITCHYAW_DATA::NAME,
35139 GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID,
35140 ),
35141 (
35142 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::NAME,
35143 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID,
35144 ),
35145 (ESC_INFO_DATA::NAME, ESC_INFO_DATA::ID),
35146 (ESC_STATUS_DATA::NAME, ESC_STATUS_DATA::ID),
35147 (WIFI_CONFIG_AP_DATA::NAME, WIFI_CONFIG_AP_DATA::ID),
35148 (PROTOCOL_VERSION_DATA::NAME, PROTOCOL_VERSION_DATA::ID),
35149 (AIS_VESSEL_DATA::NAME, AIS_VESSEL_DATA::ID),
35150 (UAVCAN_NODE_STATUS_DATA::NAME, UAVCAN_NODE_STATUS_DATA::ID),
35151 (UAVCAN_NODE_INFO_DATA::NAME, UAVCAN_NODE_INFO_DATA::ID),
35152 (
35153 PARAM_EXT_REQUEST_READ_DATA::NAME,
35154 PARAM_EXT_REQUEST_READ_DATA::ID,
35155 ),
35156 (
35157 PARAM_EXT_REQUEST_LIST_DATA::NAME,
35158 PARAM_EXT_REQUEST_LIST_DATA::ID,
35159 ),
35160 (PARAM_EXT_VALUE_DATA::NAME, PARAM_EXT_VALUE_DATA::ID),
35161 (PARAM_EXT_SET_DATA::NAME, PARAM_EXT_SET_DATA::ID),
35162 (PARAM_EXT_ACK_DATA::NAME, PARAM_EXT_ACK_DATA::ID),
35163 (OBSTACLE_DISTANCE_DATA::NAME, OBSTACLE_DISTANCE_DATA::ID),
35164 (ODOMETRY_DATA::NAME, ODOMETRY_DATA::ID),
35165 (
35166 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::NAME,
35167 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID,
35168 ),
35169 (
35170 TRAJECTORY_REPRESENTATION_BEZIER_DATA::NAME,
35171 TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID,
35172 ),
35173 (CELLULAR_STATUS_DATA::NAME, CELLULAR_STATUS_DATA::ID),
35174 (ISBD_LINK_STATUS_DATA::NAME, ISBD_LINK_STATUS_DATA::ID),
35175 (CELLULAR_CONFIG_DATA::NAME, CELLULAR_CONFIG_DATA::ID),
35176 (RAW_RPM_DATA::NAME, RAW_RPM_DATA::ID),
35177 (UTM_GLOBAL_POSITION_DATA::NAME, UTM_GLOBAL_POSITION_DATA::ID),
35178 (DEBUG_FLOAT_ARRAY_DATA::NAME, DEBUG_FLOAT_ARRAY_DATA::ID),
35179 (
35180 ORBIT_EXECUTION_STATUS_DATA::NAME,
35181 ORBIT_EXECUTION_STATUS_DATA::ID,
35182 ),
35183 (SMART_BATTERY_INFO_DATA::NAME, SMART_BATTERY_INFO_DATA::ID),
35184 (FUEL_STATUS_DATA::NAME, FUEL_STATUS_DATA::ID),
35185 (BATTERY_INFO_DATA::NAME, BATTERY_INFO_DATA::ID),
35186 (GENERATOR_STATUS_DATA::NAME, GENERATOR_STATUS_DATA::ID),
35187 (
35188 ACTUATOR_OUTPUT_STATUS_DATA::NAME,
35189 ACTUATOR_OUTPUT_STATUS_DATA::ID,
35190 ),
35191 (
35192 TIME_ESTIMATE_TO_TARGET_DATA::NAME,
35193 TIME_ESTIMATE_TO_TARGET_DATA::ID,
35194 ),
35195 (TUNNEL_DATA::NAME, TUNNEL_DATA::ID),
35196 (CAN_FRAME_DATA::NAME, CAN_FRAME_DATA::ID),
35197 (CANFD_FRAME_DATA::NAME, CANFD_FRAME_DATA::ID),
35198 (CAN_FILTER_MODIFY_DATA::NAME, CAN_FILTER_MODIFY_DATA::ID),
35199 (
35200 ONBOARD_COMPUTER_STATUS_DATA::NAME,
35201 ONBOARD_COMPUTER_STATUS_DATA::ID,
35202 ),
35203 (
35204 COMPONENT_INFORMATION_DATA::NAME,
35205 COMPONENT_INFORMATION_DATA::ID,
35206 ),
35207 (
35208 COMPONENT_INFORMATION_BASIC_DATA::NAME,
35209 COMPONENT_INFORMATION_BASIC_DATA::ID,
35210 ),
35211 (COMPONENT_METADATA_DATA::NAME, COMPONENT_METADATA_DATA::ID),
35212 (PLAY_TUNE_V2_DATA::NAME, PLAY_TUNE_V2_DATA::ID),
35213 (SUPPORTED_TUNES_DATA::NAME, SUPPORTED_TUNES_DATA::ID),
35214 (EVENT_DATA::NAME, EVENT_DATA::ID),
35215 (
35216 CURRENT_EVENT_SEQUENCE_DATA::NAME,
35217 CURRENT_EVENT_SEQUENCE_DATA::ID,
35218 ),
35219 (REQUEST_EVENT_DATA::NAME, REQUEST_EVENT_DATA::ID),
35220 (
35221 RESPONSE_EVENT_ERROR_DATA::NAME,
35222 RESPONSE_EVENT_ERROR_DATA::ID,
35223 ),
35224 (AVAILABLE_MODES_DATA::NAME, AVAILABLE_MODES_DATA::ID),
35225 (CURRENT_MODE_DATA::NAME, CURRENT_MODE_DATA::ID),
35226 (
35227 AVAILABLE_MODES_MONITOR_DATA::NAME,
35228 AVAILABLE_MODES_MONITOR_DATA::ID,
35229 ),
35230 (ILLUMINATOR_STATUS_DATA::NAME, ILLUMINATOR_STATUS_DATA::ID),
35231 (WHEEL_DISTANCE_DATA::NAME, WHEEL_DISTANCE_DATA::ID),
35232 (WINCH_STATUS_DATA::NAME, WINCH_STATUS_DATA::ID),
35233 (
35234 OPEN_DRONE_ID_BASIC_ID_DATA::NAME,
35235 OPEN_DRONE_ID_BASIC_ID_DATA::ID,
35236 ),
35237 (
35238 OPEN_DRONE_ID_LOCATION_DATA::NAME,
35239 OPEN_DRONE_ID_LOCATION_DATA::ID,
35240 ),
35241 (
35242 OPEN_DRONE_ID_AUTHENTICATION_DATA::NAME,
35243 OPEN_DRONE_ID_AUTHENTICATION_DATA::ID,
35244 ),
35245 (
35246 OPEN_DRONE_ID_SELF_ID_DATA::NAME,
35247 OPEN_DRONE_ID_SELF_ID_DATA::ID,
35248 ),
35249 (
35250 OPEN_DRONE_ID_SYSTEM_DATA::NAME,
35251 OPEN_DRONE_ID_SYSTEM_DATA::ID,
35252 ),
35253 (
35254 OPEN_DRONE_ID_OPERATOR_ID_DATA::NAME,
35255 OPEN_DRONE_ID_OPERATOR_ID_DATA::ID,
35256 ),
35257 (
35258 OPEN_DRONE_ID_MESSAGE_PACK_DATA::NAME,
35259 OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID,
35260 ),
35261 (
35262 OPEN_DRONE_ID_ARM_STATUS_DATA::NAME,
35263 OPEN_DRONE_ID_ARM_STATUS_DATA::ID,
35264 ),
35265 (
35266 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::NAME,
35267 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID,
35268 ),
35269 (HYGROMETER_SENSOR_DATA::NAME, HYGROMETER_SENSOR_DATA::ID),
35270 ]
35271 }
35272}
35273impl Message for MavMessage {
35274 fn parse(
35275 version: MavlinkVersion,
35276 id: u32,
35277 payload: &[u8],
35278 ) -> Result<Self, ::mavlink_core::error::ParserError> {
35279 match id {
35280 ACTUATOR_CONTROL_TARGET_DATA::ID => {
35281 ACTUATOR_CONTROL_TARGET_DATA::deser(version, payload)
35282 .map(Self::ACTUATOR_CONTROL_TARGET)
35283 }
35284 ACTUATOR_OUTPUT_STATUS_DATA::ID => ACTUATOR_OUTPUT_STATUS_DATA::deser(version, payload)
35285 .map(Self::ACTUATOR_OUTPUT_STATUS),
35286 ADSB_VEHICLE_DATA::ID => {
35287 ADSB_VEHICLE_DATA::deser(version, payload).map(Self::ADSB_VEHICLE)
35288 }
35289 AIS_VESSEL_DATA::ID => AIS_VESSEL_DATA::deser(version, payload).map(Self::AIS_VESSEL),
35290 ALTITUDE_DATA::ID => ALTITUDE_DATA::deser(version, payload).map(Self::ALTITUDE),
35291 ATTITUDE_DATA::ID => ATTITUDE_DATA::deser(version, payload).map(Self::ATTITUDE),
35292 ATTITUDE_QUATERNION_DATA::ID => {
35293 ATTITUDE_QUATERNION_DATA::deser(version, payload).map(Self::ATTITUDE_QUATERNION)
35294 }
35295 ATTITUDE_QUATERNION_COV_DATA::ID => {
35296 ATTITUDE_QUATERNION_COV_DATA::deser(version, payload)
35297 .map(Self::ATTITUDE_QUATERNION_COV)
35298 }
35299 ATTITUDE_TARGET_DATA::ID => {
35300 ATTITUDE_TARGET_DATA::deser(version, payload).map(Self::ATTITUDE_TARGET)
35301 }
35302 ATT_POS_MOCAP_DATA::ID => {
35303 ATT_POS_MOCAP_DATA::deser(version, payload).map(Self::ATT_POS_MOCAP)
35304 }
35305 AUTH_KEY_DATA::ID => AUTH_KEY_DATA::deser(version, payload).map(Self::AUTH_KEY),
35306 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID => {
35307 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::deser(version, payload)
35308 .map(Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE)
35309 }
35310 AUTOPILOT_VERSION_DATA::ID => {
35311 AUTOPILOT_VERSION_DATA::deser(version, payload).map(Self::AUTOPILOT_VERSION)
35312 }
35313 AVAILABLE_MODES_DATA::ID => {
35314 AVAILABLE_MODES_DATA::deser(version, payload).map(Self::AVAILABLE_MODES)
35315 }
35316 AVAILABLE_MODES_MONITOR_DATA::ID => {
35317 AVAILABLE_MODES_MONITOR_DATA::deser(version, payload)
35318 .map(Self::AVAILABLE_MODES_MONITOR)
35319 }
35320 BATTERY_INFO_DATA::ID => {
35321 BATTERY_INFO_DATA::deser(version, payload).map(Self::BATTERY_INFO)
35322 }
35323 BATTERY_STATUS_DATA::ID => {
35324 BATTERY_STATUS_DATA::deser(version, payload).map(Self::BATTERY_STATUS)
35325 }
35326 BUTTON_CHANGE_DATA::ID => {
35327 BUTTON_CHANGE_DATA::deser(version, payload).map(Self::BUTTON_CHANGE)
35328 }
35329 CAMERA_CAPTURE_STATUS_DATA::ID => {
35330 CAMERA_CAPTURE_STATUS_DATA::deser(version, payload).map(Self::CAMERA_CAPTURE_STATUS)
35331 }
35332 CAMERA_FOV_STATUS_DATA::ID => {
35333 CAMERA_FOV_STATUS_DATA::deser(version, payload).map(Self::CAMERA_FOV_STATUS)
35334 }
35335 CAMERA_IMAGE_CAPTURED_DATA::ID => {
35336 CAMERA_IMAGE_CAPTURED_DATA::deser(version, payload).map(Self::CAMERA_IMAGE_CAPTURED)
35337 }
35338 CAMERA_INFORMATION_DATA::ID => {
35339 CAMERA_INFORMATION_DATA::deser(version, payload).map(Self::CAMERA_INFORMATION)
35340 }
35341 CAMERA_SETTINGS_DATA::ID => {
35342 CAMERA_SETTINGS_DATA::deser(version, payload).map(Self::CAMERA_SETTINGS)
35343 }
35344 CAMERA_THERMAL_RANGE_DATA::ID => {
35345 CAMERA_THERMAL_RANGE_DATA::deser(version, payload).map(Self::CAMERA_THERMAL_RANGE)
35346 }
35347 CAMERA_TRACKING_GEO_STATUS_DATA::ID => {
35348 CAMERA_TRACKING_GEO_STATUS_DATA::deser(version, payload)
35349 .map(Self::CAMERA_TRACKING_GEO_STATUS)
35350 }
35351 CAMERA_TRACKING_IMAGE_STATUS_DATA::ID => {
35352 CAMERA_TRACKING_IMAGE_STATUS_DATA::deser(version, payload)
35353 .map(Self::CAMERA_TRACKING_IMAGE_STATUS)
35354 }
35355 CAMERA_TRIGGER_DATA::ID => {
35356 CAMERA_TRIGGER_DATA::deser(version, payload).map(Self::CAMERA_TRIGGER)
35357 }
35358 CANFD_FRAME_DATA::ID => {
35359 CANFD_FRAME_DATA::deser(version, payload).map(Self::CANFD_FRAME)
35360 }
35361 CAN_FILTER_MODIFY_DATA::ID => {
35362 CAN_FILTER_MODIFY_DATA::deser(version, payload).map(Self::CAN_FILTER_MODIFY)
35363 }
35364 CAN_FRAME_DATA::ID => CAN_FRAME_DATA::deser(version, payload).map(Self::CAN_FRAME),
35365 CELLULAR_CONFIG_DATA::ID => {
35366 CELLULAR_CONFIG_DATA::deser(version, payload).map(Self::CELLULAR_CONFIG)
35367 }
35368 CELLULAR_STATUS_DATA::ID => {
35369 CELLULAR_STATUS_DATA::deser(version, payload).map(Self::CELLULAR_STATUS)
35370 }
35371 CHANGE_OPERATOR_CONTROL_DATA::ID => {
35372 CHANGE_OPERATOR_CONTROL_DATA::deser(version, payload)
35373 .map(Self::CHANGE_OPERATOR_CONTROL)
35374 }
35375 CHANGE_OPERATOR_CONTROL_ACK_DATA::ID => {
35376 CHANGE_OPERATOR_CONTROL_ACK_DATA::deser(version, payload)
35377 .map(Self::CHANGE_OPERATOR_CONTROL_ACK)
35378 }
35379 COLLISION_DATA::ID => COLLISION_DATA::deser(version, payload).map(Self::COLLISION),
35380 COMMAND_ACK_DATA::ID => {
35381 COMMAND_ACK_DATA::deser(version, payload).map(Self::COMMAND_ACK)
35382 }
35383 COMMAND_CANCEL_DATA::ID => {
35384 COMMAND_CANCEL_DATA::deser(version, payload).map(Self::COMMAND_CANCEL)
35385 }
35386 COMMAND_INT_DATA::ID => {
35387 COMMAND_INT_DATA::deser(version, payload).map(Self::COMMAND_INT)
35388 }
35389 COMMAND_LONG_DATA::ID => {
35390 COMMAND_LONG_DATA::deser(version, payload).map(Self::COMMAND_LONG)
35391 }
35392 COMPONENT_INFORMATION_DATA::ID => {
35393 COMPONENT_INFORMATION_DATA::deser(version, payload).map(Self::COMPONENT_INFORMATION)
35394 }
35395 COMPONENT_INFORMATION_BASIC_DATA::ID => {
35396 COMPONENT_INFORMATION_BASIC_DATA::deser(version, payload)
35397 .map(Self::COMPONENT_INFORMATION_BASIC)
35398 }
35399 COMPONENT_METADATA_DATA::ID => {
35400 COMPONENT_METADATA_DATA::deser(version, payload).map(Self::COMPONENT_METADATA)
35401 }
35402 CONTROL_SYSTEM_STATE_DATA::ID => {
35403 CONTROL_SYSTEM_STATE_DATA::deser(version, payload).map(Self::CONTROL_SYSTEM_STATE)
35404 }
35405 CURRENT_EVENT_SEQUENCE_DATA::ID => CURRENT_EVENT_SEQUENCE_DATA::deser(version, payload)
35406 .map(Self::CURRENT_EVENT_SEQUENCE),
35407 CURRENT_MODE_DATA::ID => {
35408 CURRENT_MODE_DATA::deser(version, payload).map(Self::CURRENT_MODE)
35409 }
35410 DATA_STREAM_DATA::ID => {
35411 DATA_STREAM_DATA::deser(version, payload).map(Self::DATA_STREAM)
35412 }
35413 DATA_TRANSMISSION_HANDSHAKE_DATA::ID => {
35414 DATA_TRANSMISSION_HANDSHAKE_DATA::deser(version, payload)
35415 .map(Self::DATA_TRANSMISSION_HANDSHAKE)
35416 }
35417 DEBUG_DATA::ID => DEBUG_DATA::deser(version, payload).map(Self::DEBUG),
35418 DEBUG_FLOAT_ARRAY_DATA::ID => {
35419 DEBUG_FLOAT_ARRAY_DATA::deser(version, payload).map(Self::DEBUG_FLOAT_ARRAY)
35420 }
35421 DEBUG_VECT_DATA::ID => DEBUG_VECT_DATA::deser(version, payload).map(Self::DEBUG_VECT),
35422 DISTANCE_SENSOR_DATA::ID => {
35423 DISTANCE_SENSOR_DATA::deser(version, payload).map(Self::DISTANCE_SENSOR)
35424 }
35425 EFI_STATUS_DATA::ID => EFI_STATUS_DATA::deser(version, payload).map(Self::EFI_STATUS),
35426 ENCAPSULATED_DATA_DATA::ID => {
35427 ENCAPSULATED_DATA_DATA::deser(version, payload).map(Self::ENCAPSULATED_DATA)
35428 }
35429 ESC_INFO_DATA::ID => ESC_INFO_DATA::deser(version, payload).map(Self::ESC_INFO),
35430 ESC_STATUS_DATA::ID => ESC_STATUS_DATA::deser(version, payload).map(Self::ESC_STATUS),
35431 ESTIMATOR_STATUS_DATA::ID => {
35432 ESTIMATOR_STATUS_DATA::deser(version, payload).map(Self::ESTIMATOR_STATUS)
35433 }
35434 EVENT_DATA::ID => EVENT_DATA::deser(version, payload).map(Self::EVENT),
35435 EXTENDED_SYS_STATE_DATA::ID => {
35436 EXTENDED_SYS_STATE_DATA::deser(version, payload).map(Self::EXTENDED_SYS_STATE)
35437 }
35438 FENCE_STATUS_DATA::ID => {
35439 FENCE_STATUS_DATA::deser(version, payload).map(Self::FENCE_STATUS)
35440 }
35441 FILE_TRANSFER_PROTOCOL_DATA::ID => FILE_TRANSFER_PROTOCOL_DATA::deser(version, payload)
35442 .map(Self::FILE_TRANSFER_PROTOCOL),
35443 FLIGHT_INFORMATION_DATA::ID => {
35444 FLIGHT_INFORMATION_DATA::deser(version, payload).map(Self::FLIGHT_INFORMATION)
35445 }
35446 FOLLOW_TARGET_DATA::ID => {
35447 FOLLOW_TARGET_DATA::deser(version, payload).map(Self::FOLLOW_TARGET)
35448 }
35449 FUEL_STATUS_DATA::ID => {
35450 FUEL_STATUS_DATA::deser(version, payload).map(Self::FUEL_STATUS)
35451 }
35452 GENERATOR_STATUS_DATA::ID => {
35453 GENERATOR_STATUS_DATA::deser(version, payload).map(Self::GENERATOR_STATUS)
35454 }
35455 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID => {
35456 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::deser(version, payload)
35457 .map(Self::GIMBAL_DEVICE_ATTITUDE_STATUS)
35458 }
35459 GIMBAL_DEVICE_INFORMATION_DATA::ID => {
35460 GIMBAL_DEVICE_INFORMATION_DATA::deser(version, payload)
35461 .map(Self::GIMBAL_DEVICE_INFORMATION)
35462 }
35463 GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID => {
35464 GIMBAL_DEVICE_SET_ATTITUDE_DATA::deser(version, payload)
35465 .map(Self::GIMBAL_DEVICE_SET_ATTITUDE)
35466 }
35467 GIMBAL_MANAGER_INFORMATION_DATA::ID => {
35468 GIMBAL_MANAGER_INFORMATION_DATA::deser(version, payload)
35469 .map(Self::GIMBAL_MANAGER_INFORMATION)
35470 }
35471 GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID => {
35472 GIMBAL_MANAGER_SET_ATTITUDE_DATA::deser(version, payload)
35473 .map(Self::GIMBAL_MANAGER_SET_ATTITUDE)
35474 }
35475 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID => {
35476 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::deser(version, payload)
35477 .map(Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL)
35478 }
35479 GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID => {
35480 GIMBAL_MANAGER_SET_PITCHYAW_DATA::deser(version, payload)
35481 .map(Self::GIMBAL_MANAGER_SET_PITCHYAW)
35482 }
35483 GIMBAL_MANAGER_STATUS_DATA::ID => {
35484 GIMBAL_MANAGER_STATUS_DATA::deser(version, payload).map(Self::GIMBAL_MANAGER_STATUS)
35485 }
35486 GLOBAL_POSITION_INT_DATA::ID => {
35487 GLOBAL_POSITION_INT_DATA::deser(version, payload).map(Self::GLOBAL_POSITION_INT)
35488 }
35489 GLOBAL_POSITION_INT_COV_DATA::ID => {
35490 GLOBAL_POSITION_INT_COV_DATA::deser(version, payload)
35491 .map(Self::GLOBAL_POSITION_INT_COV)
35492 }
35493 GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID => {
35494 GLOBAL_VISION_POSITION_ESTIMATE_DATA::deser(version, payload)
35495 .map(Self::GLOBAL_VISION_POSITION_ESTIMATE)
35496 }
35497 GPS2_RAW_DATA::ID => GPS2_RAW_DATA::deser(version, payload).map(Self::GPS2_RAW),
35498 GPS2_RTK_DATA::ID => GPS2_RTK_DATA::deser(version, payload).map(Self::GPS2_RTK),
35499 GPS_GLOBAL_ORIGIN_DATA::ID => {
35500 GPS_GLOBAL_ORIGIN_DATA::deser(version, payload).map(Self::GPS_GLOBAL_ORIGIN)
35501 }
35502 GPS_INJECT_DATA_DATA::ID => {
35503 GPS_INJECT_DATA_DATA::deser(version, payload).map(Self::GPS_INJECT_DATA)
35504 }
35505 GPS_INPUT_DATA::ID => GPS_INPUT_DATA::deser(version, payload).map(Self::GPS_INPUT),
35506 GPS_RAW_INT_DATA::ID => {
35507 GPS_RAW_INT_DATA::deser(version, payload).map(Self::GPS_RAW_INT)
35508 }
35509 GPS_RTCM_DATA_DATA::ID => {
35510 GPS_RTCM_DATA_DATA::deser(version, payload).map(Self::GPS_RTCM_DATA)
35511 }
35512 GPS_RTK_DATA::ID => GPS_RTK_DATA::deser(version, payload).map(Self::GPS_RTK),
35513 GPS_STATUS_DATA::ID => GPS_STATUS_DATA::deser(version, payload).map(Self::GPS_STATUS),
35514 HEARTBEAT_DATA::ID => HEARTBEAT_DATA::deser(version, payload).map(Self::HEARTBEAT),
35515 HIGHRES_IMU_DATA::ID => {
35516 HIGHRES_IMU_DATA::deser(version, payload).map(Self::HIGHRES_IMU)
35517 }
35518 HIGH_LATENCY_DATA::ID => {
35519 HIGH_LATENCY_DATA::deser(version, payload).map(Self::HIGH_LATENCY)
35520 }
35521 HIGH_LATENCY2_DATA::ID => {
35522 HIGH_LATENCY2_DATA::deser(version, payload).map(Self::HIGH_LATENCY2)
35523 }
35524 HIL_ACTUATOR_CONTROLS_DATA::ID => {
35525 HIL_ACTUATOR_CONTROLS_DATA::deser(version, payload).map(Self::HIL_ACTUATOR_CONTROLS)
35526 }
35527 HIL_CONTROLS_DATA::ID => {
35528 HIL_CONTROLS_DATA::deser(version, payload).map(Self::HIL_CONTROLS)
35529 }
35530 HIL_GPS_DATA::ID => HIL_GPS_DATA::deser(version, payload).map(Self::HIL_GPS),
35531 HIL_OPTICAL_FLOW_DATA::ID => {
35532 HIL_OPTICAL_FLOW_DATA::deser(version, payload).map(Self::HIL_OPTICAL_FLOW)
35533 }
35534 HIL_RC_INPUTS_RAW_DATA::ID => {
35535 HIL_RC_INPUTS_RAW_DATA::deser(version, payload).map(Self::HIL_RC_INPUTS_RAW)
35536 }
35537 HIL_SENSOR_DATA::ID => HIL_SENSOR_DATA::deser(version, payload).map(Self::HIL_SENSOR),
35538 HIL_STATE_DATA::ID => HIL_STATE_DATA::deser(version, payload).map(Self::HIL_STATE),
35539 HIL_STATE_QUATERNION_DATA::ID => {
35540 HIL_STATE_QUATERNION_DATA::deser(version, payload).map(Self::HIL_STATE_QUATERNION)
35541 }
35542 HOME_POSITION_DATA::ID => {
35543 HOME_POSITION_DATA::deser(version, payload).map(Self::HOME_POSITION)
35544 }
35545 HYGROMETER_SENSOR_DATA::ID => {
35546 HYGROMETER_SENSOR_DATA::deser(version, payload).map(Self::HYGROMETER_SENSOR)
35547 }
35548 ILLUMINATOR_STATUS_DATA::ID => {
35549 ILLUMINATOR_STATUS_DATA::deser(version, payload).map(Self::ILLUMINATOR_STATUS)
35550 }
35551 ISBD_LINK_STATUS_DATA::ID => {
35552 ISBD_LINK_STATUS_DATA::deser(version, payload).map(Self::ISBD_LINK_STATUS)
35553 }
35554 LANDING_TARGET_DATA::ID => {
35555 LANDING_TARGET_DATA::deser(version, payload).map(Self::LANDING_TARGET)
35556 }
35557 LINK_NODE_STATUS_DATA::ID => {
35558 LINK_NODE_STATUS_DATA::deser(version, payload).map(Self::LINK_NODE_STATUS)
35559 }
35560 LOCAL_POSITION_NED_DATA::ID => {
35561 LOCAL_POSITION_NED_DATA::deser(version, payload).map(Self::LOCAL_POSITION_NED)
35562 }
35563 LOCAL_POSITION_NED_COV_DATA::ID => LOCAL_POSITION_NED_COV_DATA::deser(version, payload)
35564 .map(Self::LOCAL_POSITION_NED_COV),
35565 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID => {
35566 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::deser(version, payload)
35567 .map(Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET)
35568 }
35569 LOGGING_ACK_DATA::ID => {
35570 LOGGING_ACK_DATA::deser(version, payload).map(Self::LOGGING_ACK)
35571 }
35572 LOGGING_DATA_DATA::ID => {
35573 LOGGING_DATA_DATA::deser(version, payload).map(Self::LOGGING_DATA)
35574 }
35575 LOGGING_DATA_ACKED_DATA::ID => {
35576 LOGGING_DATA_ACKED_DATA::deser(version, payload).map(Self::LOGGING_DATA_ACKED)
35577 }
35578 LOG_DATA_DATA::ID => LOG_DATA_DATA::deser(version, payload).map(Self::LOG_DATA),
35579 LOG_ENTRY_DATA::ID => LOG_ENTRY_DATA::deser(version, payload).map(Self::LOG_ENTRY),
35580 LOG_ERASE_DATA::ID => LOG_ERASE_DATA::deser(version, payload).map(Self::LOG_ERASE),
35581 LOG_REQUEST_DATA_DATA::ID => {
35582 LOG_REQUEST_DATA_DATA::deser(version, payload).map(Self::LOG_REQUEST_DATA)
35583 }
35584 LOG_REQUEST_END_DATA::ID => {
35585 LOG_REQUEST_END_DATA::deser(version, payload).map(Self::LOG_REQUEST_END)
35586 }
35587 LOG_REQUEST_LIST_DATA::ID => {
35588 LOG_REQUEST_LIST_DATA::deser(version, payload).map(Self::LOG_REQUEST_LIST)
35589 }
35590 MAG_CAL_REPORT_DATA::ID => {
35591 MAG_CAL_REPORT_DATA::deser(version, payload).map(Self::MAG_CAL_REPORT)
35592 }
35593 MANUAL_CONTROL_DATA::ID => {
35594 MANUAL_CONTROL_DATA::deser(version, payload).map(Self::MANUAL_CONTROL)
35595 }
35596 MANUAL_SETPOINT_DATA::ID => {
35597 MANUAL_SETPOINT_DATA::deser(version, payload).map(Self::MANUAL_SETPOINT)
35598 }
35599 MEMORY_VECT_DATA::ID => {
35600 MEMORY_VECT_DATA::deser(version, payload).map(Self::MEMORY_VECT)
35601 }
35602 MESSAGE_INTERVAL_DATA::ID => {
35603 MESSAGE_INTERVAL_DATA::deser(version, payload).map(Self::MESSAGE_INTERVAL)
35604 }
35605 MISSION_ACK_DATA::ID => {
35606 MISSION_ACK_DATA::deser(version, payload).map(Self::MISSION_ACK)
35607 }
35608 MISSION_CLEAR_ALL_DATA::ID => {
35609 MISSION_CLEAR_ALL_DATA::deser(version, payload).map(Self::MISSION_CLEAR_ALL)
35610 }
35611 MISSION_COUNT_DATA::ID => {
35612 MISSION_COUNT_DATA::deser(version, payload).map(Self::MISSION_COUNT)
35613 }
35614 MISSION_CURRENT_DATA::ID => {
35615 MISSION_CURRENT_DATA::deser(version, payload).map(Self::MISSION_CURRENT)
35616 }
35617 MISSION_ITEM_DATA::ID => {
35618 MISSION_ITEM_DATA::deser(version, payload).map(Self::MISSION_ITEM)
35619 }
35620 MISSION_ITEM_INT_DATA::ID => {
35621 MISSION_ITEM_INT_DATA::deser(version, payload).map(Self::MISSION_ITEM_INT)
35622 }
35623 MISSION_ITEM_REACHED_DATA::ID => {
35624 MISSION_ITEM_REACHED_DATA::deser(version, payload).map(Self::MISSION_ITEM_REACHED)
35625 }
35626 MISSION_REQUEST_DATA::ID => {
35627 MISSION_REQUEST_DATA::deser(version, payload).map(Self::MISSION_REQUEST)
35628 }
35629 MISSION_REQUEST_INT_DATA::ID => {
35630 MISSION_REQUEST_INT_DATA::deser(version, payload).map(Self::MISSION_REQUEST_INT)
35631 }
35632 MISSION_REQUEST_LIST_DATA::ID => {
35633 MISSION_REQUEST_LIST_DATA::deser(version, payload).map(Self::MISSION_REQUEST_LIST)
35634 }
35635 MISSION_REQUEST_PARTIAL_LIST_DATA::ID => {
35636 MISSION_REQUEST_PARTIAL_LIST_DATA::deser(version, payload)
35637 .map(Self::MISSION_REQUEST_PARTIAL_LIST)
35638 }
35639 MISSION_SET_CURRENT_DATA::ID => {
35640 MISSION_SET_CURRENT_DATA::deser(version, payload).map(Self::MISSION_SET_CURRENT)
35641 }
35642 MISSION_WRITE_PARTIAL_LIST_DATA::ID => {
35643 MISSION_WRITE_PARTIAL_LIST_DATA::deser(version, payload)
35644 .map(Self::MISSION_WRITE_PARTIAL_LIST)
35645 }
35646 MOUNT_ORIENTATION_DATA::ID => {
35647 MOUNT_ORIENTATION_DATA::deser(version, payload).map(Self::MOUNT_ORIENTATION)
35648 }
35649 NAMED_VALUE_FLOAT_DATA::ID => {
35650 NAMED_VALUE_FLOAT_DATA::deser(version, payload).map(Self::NAMED_VALUE_FLOAT)
35651 }
35652 NAMED_VALUE_INT_DATA::ID => {
35653 NAMED_VALUE_INT_DATA::deser(version, payload).map(Self::NAMED_VALUE_INT)
35654 }
35655 NAV_CONTROLLER_OUTPUT_DATA::ID => {
35656 NAV_CONTROLLER_OUTPUT_DATA::deser(version, payload).map(Self::NAV_CONTROLLER_OUTPUT)
35657 }
35658 OBSTACLE_DISTANCE_DATA::ID => {
35659 OBSTACLE_DISTANCE_DATA::deser(version, payload).map(Self::OBSTACLE_DISTANCE)
35660 }
35661 ODOMETRY_DATA::ID => ODOMETRY_DATA::deser(version, payload).map(Self::ODOMETRY),
35662 ONBOARD_COMPUTER_STATUS_DATA::ID => {
35663 ONBOARD_COMPUTER_STATUS_DATA::deser(version, payload)
35664 .map(Self::ONBOARD_COMPUTER_STATUS)
35665 }
35666 OPEN_DRONE_ID_ARM_STATUS_DATA::ID => {
35667 OPEN_DRONE_ID_ARM_STATUS_DATA::deser(version, payload)
35668 .map(Self::OPEN_DRONE_ID_ARM_STATUS)
35669 }
35670 OPEN_DRONE_ID_AUTHENTICATION_DATA::ID => {
35671 OPEN_DRONE_ID_AUTHENTICATION_DATA::deser(version, payload)
35672 .map(Self::OPEN_DRONE_ID_AUTHENTICATION)
35673 }
35674 OPEN_DRONE_ID_BASIC_ID_DATA::ID => OPEN_DRONE_ID_BASIC_ID_DATA::deser(version, payload)
35675 .map(Self::OPEN_DRONE_ID_BASIC_ID),
35676 OPEN_DRONE_ID_LOCATION_DATA::ID => OPEN_DRONE_ID_LOCATION_DATA::deser(version, payload)
35677 .map(Self::OPEN_DRONE_ID_LOCATION),
35678 OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID => {
35679 OPEN_DRONE_ID_MESSAGE_PACK_DATA::deser(version, payload)
35680 .map(Self::OPEN_DRONE_ID_MESSAGE_PACK)
35681 }
35682 OPEN_DRONE_ID_OPERATOR_ID_DATA::ID => {
35683 OPEN_DRONE_ID_OPERATOR_ID_DATA::deser(version, payload)
35684 .map(Self::OPEN_DRONE_ID_OPERATOR_ID)
35685 }
35686 OPEN_DRONE_ID_SELF_ID_DATA::ID => {
35687 OPEN_DRONE_ID_SELF_ID_DATA::deser(version, payload).map(Self::OPEN_DRONE_ID_SELF_ID)
35688 }
35689 OPEN_DRONE_ID_SYSTEM_DATA::ID => {
35690 OPEN_DRONE_ID_SYSTEM_DATA::deser(version, payload).map(Self::OPEN_DRONE_ID_SYSTEM)
35691 }
35692 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID => {
35693 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::deser(version, payload)
35694 .map(Self::OPEN_DRONE_ID_SYSTEM_UPDATE)
35695 }
35696 OPTICAL_FLOW_DATA::ID => {
35697 OPTICAL_FLOW_DATA::deser(version, payload).map(Self::OPTICAL_FLOW)
35698 }
35699 OPTICAL_FLOW_RAD_DATA::ID => {
35700 OPTICAL_FLOW_RAD_DATA::deser(version, payload).map(Self::OPTICAL_FLOW_RAD)
35701 }
35702 ORBIT_EXECUTION_STATUS_DATA::ID => ORBIT_EXECUTION_STATUS_DATA::deser(version, payload)
35703 .map(Self::ORBIT_EXECUTION_STATUS),
35704 PARAM_EXT_ACK_DATA::ID => {
35705 PARAM_EXT_ACK_DATA::deser(version, payload).map(Self::PARAM_EXT_ACK)
35706 }
35707 PARAM_EXT_REQUEST_LIST_DATA::ID => PARAM_EXT_REQUEST_LIST_DATA::deser(version, payload)
35708 .map(Self::PARAM_EXT_REQUEST_LIST),
35709 PARAM_EXT_REQUEST_READ_DATA::ID => PARAM_EXT_REQUEST_READ_DATA::deser(version, payload)
35710 .map(Self::PARAM_EXT_REQUEST_READ),
35711 PARAM_EXT_SET_DATA::ID => {
35712 PARAM_EXT_SET_DATA::deser(version, payload).map(Self::PARAM_EXT_SET)
35713 }
35714 PARAM_EXT_VALUE_DATA::ID => {
35715 PARAM_EXT_VALUE_DATA::deser(version, payload).map(Self::PARAM_EXT_VALUE)
35716 }
35717 PARAM_MAP_RC_DATA::ID => {
35718 PARAM_MAP_RC_DATA::deser(version, payload).map(Self::PARAM_MAP_RC)
35719 }
35720 PARAM_REQUEST_LIST_DATA::ID => {
35721 PARAM_REQUEST_LIST_DATA::deser(version, payload).map(Self::PARAM_REQUEST_LIST)
35722 }
35723 PARAM_REQUEST_READ_DATA::ID => {
35724 PARAM_REQUEST_READ_DATA::deser(version, payload).map(Self::PARAM_REQUEST_READ)
35725 }
35726 PARAM_SET_DATA::ID => PARAM_SET_DATA::deser(version, payload).map(Self::PARAM_SET),
35727 PARAM_VALUE_DATA::ID => {
35728 PARAM_VALUE_DATA::deser(version, payload).map(Self::PARAM_VALUE)
35729 }
35730 PING_DATA::ID => PING_DATA::deser(version, payload).map(Self::PING),
35731 PLAY_TUNE_DATA::ID => PLAY_TUNE_DATA::deser(version, payload).map(Self::PLAY_TUNE),
35732 PLAY_TUNE_V2_DATA::ID => {
35733 PLAY_TUNE_V2_DATA::deser(version, payload).map(Self::PLAY_TUNE_V2)
35734 }
35735 POSITION_TARGET_GLOBAL_INT_DATA::ID => {
35736 POSITION_TARGET_GLOBAL_INT_DATA::deser(version, payload)
35737 .map(Self::POSITION_TARGET_GLOBAL_INT)
35738 }
35739 POSITION_TARGET_LOCAL_NED_DATA::ID => {
35740 POSITION_TARGET_LOCAL_NED_DATA::deser(version, payload)
35741 .map(Self::POSITION_TARGET_LOCAL_NED)
35742 }
35743 POWER_STATUS_DATA::ID => {
35744 POWER_STATUS_DATA::deser(version, payload).map(Self::POWER_STATUS)
35745 }
35746 PROTOCOL_VERSION_DATA::ID => {
35747 PROTOCOL_VERSION_DATA::deser(version, payload).map(Self::PROTOCOL_VERSION)
35748 }
35749 RADIO_STATUS_DATA::ID => {
35750 RADIO_STATUS_DATA::deser(version, payload).map(Self::RADIO_STATUS)
35751 }
35752 RAW_IMU_DATA::ID => RAW_IMU_DATA::deser(version, payload).map(Self::RAW_IMU),
35753 RAW_PRESSURE_DATA::ID => {
35754 RAW_PRESSURE_DATA::deser(version, payload).map(Self::RAW_PRESSURE)
35755 }
35756 RAW_RPM_DATA::ID => RAW_RPM_DATA::deser(version, payload).map(Self::RAW_RPM),
35757 RC_CHANNELS_DATA::ID => {
35758 RC_CHANNELS_DATA::deser(version, payload).map(Self::RC_CHANNELS)
35759 }
35760 RC_CHANNELS_OVERRIDE_DATA::ID => {
35761 RC_CHANNELS_OVERRIDE_DATA::deser(version, payload).map(Self::RC_CHANNELS_OVERRIDE)
35762 }
35763 RC_CHANNELS_RAW_DATA::ID => {
35764 RC_CHANNELS_RAW_DATA::deser(version, payload).map(Self::RC_CHANNELS_RAW)
35765 }
35766 RC_CHANNELS_SCALED_DATA::ID => {
35767 RC_CHANNELS_SCALED_DATA::deser(version, payload).map(Self::RC_CHANNELS_SCALED)
35768 }
35769 REQUEST_DATA_STREAM_DATA::ID => {
35770 REQUEST_DATA_STREAM_DATA::deser(version, payload).map(Self::REQUEST_DATA_STREAM)
35771 }
35772 REQUEST_EVENT_DATA::ID => {
35773 REQUEST_EVENT_DATA::deser(version, payload).map(Self::REQUEST_EVENT)
35774 }
35775 RESOURCE_REQUEST_DATA::ID => {
35776 RESOURCE_REQUEST_DATA::deser(version, payload).map(Self::RESOURCE_REQUEST)
35777 }
35778 RESPONSE_EVENT_ERROR_DATA::ID => {
35779 RESPONSE_EVENT_ERROR_DATA::deser(version, payload).map(Self::RESPONSE_EVENT_ERROR)
35780 }
35781 SAFETY_ALLOWED_AREA_DATA::ID => {
35782 SAFETY_ALLOWED_AREA_DATA::deser(version, payload).map(Self::SAFETY_ALLOWED_AREA)
35783 }
35784 SAFETY_SET_ALLOWED_AREA_DATA::ID => {
35785 SAFETY_SET_ALLOWED_AREA_DATA::deser(version, payload)
35786 .map(Self::SAFETY_SET_ALLOWED_AREA)
35787 }
35788 SCALED_IMU_DATA::ID => SCALED_IMU_DATA::deser(version, payload).map(Self::SCALED_IMU),
35789 SCALED_IMU2_DATA::ID => {
35790 SCALED_IMU2_DATA::deser(version, payload).map(Self::SCALED_IMU2)
35791 }
35792 SCALED_IMU3_DATA::ID => {
35793 SCALED_IMU3_DATA::deser(version, payload).map(Self::SCALED_IMU3)
35794 }
35795 SCALED_PRESSURE_DATA::ID => {
35796 SCALED_PRESSURE_DATA::deser(version, payload).map(Self::SCALED_PRESSURE)
35797 }
35798 SCALED_PRESSURE2_DATA::ID => {
35799 SCALED_PRESSURE2_DATA::deser(version, payload).map(Self::SCALED_PRESSURE2)
35800 }
35801 SCALED_PRESSURE3_DATA::ID => {
35802 SCALED_PRESSURE3_DATA::deser(version, payload).map(Self::SCALED_PRESSURE3)
35803 }
35804 SERIAL_CONTROL_DATA::ID => {
35805 SERIAL_CONTROL_DATA::deser(version, payload).map(Self::SERIAL_CONTROL)
35806 }
35807 SERVO_OUTPUT_RAW_DATA::ID => {
35808 SERVO_OUTPUT_RAW_DATA::deser(version, payload).map(Self::SERVO_OUTPUT_RAW)
35809 }
35810 SETUP_SIGNING_DATA::ID => {
35811 SETUP_SIGNING_DATA::deser(version, payload).map(Self::SETUP_SIGNING)
35812 }
35813 SET_ACTUATOR_CONTROL_TARGET_DATA::ID => {
35814 SET_ACTUATOR_CONTROL_TARGET_DATA::deser(version, payload)
35815 .map(Self::SET_ACTUATOR_CONTROL_TARGET)
35816 }
35817 SET_ATTITUDE_TARGET_DATA::ID => {
35818 SET_ATTITUDE_TARGET_DATA::deser(version, payload).map(Self::SET_ATTITUDE_TARGET)
35819 }
35820 SET_GPS_GLOBAL_ORIGIN_DATA::ID => {
35821 SET_GPS_GLOBAL_ORIGIN_DATA::deser(version, payload).map(Self::SET_GPS_GLOBAL_ORIGIN)
35822 }
35823 SET_HOME_POSITION_DATA::ID => {
35824 SET_HOME_POSITION_DATA::deser(version, payload).map(Self::SET_HOME_POSITION)
35825 }
35826 SET_MODE_DATA::ID => SET_MODE_DATA::deser(version, payload).map(Self::SET_MODE),
35827 SET_POSITION_TARGET_GLOBAL_INT_DATA::ID => {
35828 SET_POSITION_TARGET_GLOBAL_INT_DATA::deser(version, payload)
35829 .map(Self::SET_POSITION_TARGET_GLOBAL_INT)
35830 }
35831 SET_POSITION_TARGET_LOCAL_NED_DATA::ID => {
35832 SET_POSITION_TARGET_LOCAL_NED_DATA::deser(version, payload)
35833 .map(Self::SET_POSITION_TARGET_LOCAL_NED)
35834 }
35835 SIM_STATE_DATA::ID => SIM_STATE_DATA::deser(version, payload).map(Self::SIM_STATE),
35836 SMART_BATTERY_INFO_DATA::ID => {
35837 SMART_BATTERY_INFO_DATA::deser(version, payload).map(Self::SMART_BATTERY_INFO)
35838 }
35839 STATUSTEXT_DATA::ID => STATUSTEXT_DATA::deser(version, payload).map(Self::STATUSTEXT),
35840 STORAGE_INFORMATION_DATA::ID => {
35841 STORAGE_INFORMATION_DATA::deser(version, payload).map(Self::STORAGE_INFORMATION)
35842 }
35843 SUPPORTED_TUNES_DATA::ID => {
35844 SUPPORTED_TUNES_DATA::deser(version, payload).map(Self::SUPPORTED_TUNES)
35845 }
35846 SYSTEM_TIME_DATA::ID => {
35847 SYSTEM_TIME_DATA::deser(version, payload).map(Self::SYSTEM_TIME)
35848 }
35849 SYS_STATUS_DATA::ID => SYS_STATUS_DATA::deser(version, payload).map(Self::SYS_STATUS),
35850 TERRAIN_CHECK_DATA::ID => {
35851 TERRAIN_CHECK_DATA::deser(version, payload).map(Self::TERRAIN_CHECK)
35852 }
35853 TERRAIN_DATA_DATA::ID => {
35854 TERRAIN_DATA_DATA::deser(version, payload).map(Self::TERRAIN_DATA)
35855 }
35856 TERRAIN_REPORT_DATA::ID => {
35857 TERRAIN_REPORT_DATA::deser(version, payload).map(Self::TERRAIN_REPORT)
35858 }
35859 TERRAIN_REQUEST_DATA::ID => {
35860 TERRAIN_REQUEST_DATA::deser(version, payload).map(Self::TERRAIN_REQUEST)
35861 }
35862 TIMESYNC_DATA::ID => TIMESYNC_DATA::deser(version, payload).map(Self::TIMESYNC),
35863 TIME_ESTIMATE_TO_TARGET_DATA::ID => {
35864 TIME_ESTIMATE_TO_TARGET_DATA::deser(version, payload)
35865 .map(Self::TIME_ESTIMATE_TO_TARGET)
35866 }
35867 TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID => {
35868 TRAJECTORY_REPRESENTATION_BEZIER_DATA::deser(version, payload)
35869 .map(Self::TRAJECTORY_REPRESENTATION_BEZIER)
35870 }
35871 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID => {
35872 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::deser(version, payload)
35873 .map(Self::TRAJECTORY_REPRESENTATION_WAYPOINTS)
35874 }
35875 TUNNEL_DATA::ID => TUNNEL_DATA::deser(version, payload).map(Self::TUNNEL),
35876 UAVCAN_NODE_INFO_DATA::ID => {
35877 UAVCAN_NODE_INFO_DATA::deser(version, payload).map(Self::UAVCAN_NODE_INFO)
35878 }
35879 UAVCAN_NODE_STATUS_DATA::ID => {
35880 UAVCAN_NODE_STATUS_DATA::deser(version, payload).map(Self::UAVCAN_NODE_STATUS)
35881 }
35882 UTM_GLOBAL_POSITION_DATA::ID => {
35883 UTM_GLOBAL_POSITION_DATA::deser(version, payload).map(Self::UTM_GLOBAL_POSITION)
35884 }
35885 V2_EXTENSION_DATA::ID => {
35886 V2_EXTENSION_DATA::deser(version, payload).map(Self::V2_EXTENSION)
35887 }
35888 VFR_HUD_DATA::ID => VFR_HUD_DATA::deser(version, payload).map(Self::VFR_HUD),
35889 VIBRATION_DATA::ID => VIBRATION_DATA::deser(version, payload).map(Self::VIBRATION),
35890 VICON_POSITION_ESTIMATE_DATA::ID => {
35891 VICON_POSITION_ESTIMATE_DATA::deser(version, payload)
35892 .map(Self::VICON_POSITION_ESTIMATE)
35893 }
35894 VIDEO_STREAM_INFORMATION_DATA::ID => {
35895 VIDEO_STREAM_INFORMATION_DATA::deser(version, payload)
35896 .map(Self::VIDEO_STREAM_INFORMATION)
35897 }
35898 VIDEO_STREAM_STATUS_DATA::ID => {
35899 VIDEO_STREAM_STATUS_DATA::deser(version, payload).map(Self::VIDEO_STREAM_STATUS)
35900 }
35901 VISION_POSITION_ESTIMATE_DATA::ID => {
35902 VISION_POSITION_ESTIMATE_DATA::deser(version, payload)
35903 .map(Self::VISION_POSITION_ESTIMATE)
35904 }
35905 VISION_SPEED_ESTIMATE_DATA::ID => {
35906 VISION_SPEED_ESTIMATE_DATA::deser(version, payload).map(Self::VISION_SPEED_ESTIMATE)
35907 }
35908 WHEEL_DISTANCE_DATA::ID => {
35909 WHEEL_DISTANCE_DATA::deser(version, payload).map(Self::WHEEL_DISTANCE)
35910 }
35911 WIFI_CONFIG_AP_DATA::ID => {
35912 WIFI_CONFIG_AP_DATA::deser(version, payload).map(Self::WIFI_CONFIG_AP)
35913 }
35914 WINCH_STATUS_DATA::ID => {
35915 WINCH_STATUS_DATA::deser(version, payload).map(Self::WINCH_STATUS)
35916 }
35917 WIND_COV_DATA::ID => WIND_COV_DATA::deser(version, payload).map(Self::WIND_COV),
35918 _ => Err(::mavlink_core::error::ParserError::UnknownMessage { id }),
35919 }
35920 }
35921 fn message_name(&self) -> &'static str {
35922 match self {
35923 Self::ACTUATOR_CONTROL_TARGET(..) => ACTUATOR_CONTROL_TARGET_DATA::NAME,
35924 Self::ACTUATOR_OUTPUT_STATUS(..) => ACTUATOR_OUTPUT_STATUS_DATA::NAME,
35925 Self::ADSB_VEHICLE(..) => ADSB_VEHICLE_DATA::NAME,
35926 Self::AIS_VESSEL(..) => AIS_VESSEL_DATA::NAME,
35927 Self::ALTITUDE(..) => ALTITUDE_DATA::NAME,
35928 Self::ATTITUDE(..) => ATTITUDE_DATA::NAME,
35929 Self::ATTITUDE_QUATERNION(..) => ATTITUDE_QUATERNION_DATA::NAME,
35930 Self::ATTITUDE_QUATERNION_COV(..) => ATTITUDE_QUATERNION_COV_DATA::NAME,
35931 Self::ATTITUDE_TARGET(..) => ATTITUDE_TARGET_DATA::NAME,
35932 Self::ATT_POS_MOCAP(..) => ATT_POS_MOCAP_DATA::NAME,
35933 Self::AUTH_KEY(..) => AUTH_KEY_DATA::NAME,
35934 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(..) => {
35935 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::NAME
35936 }
35937 Self::AUTOPILOT_VERSION(..) => AUTOPILOT_VERSION_DATA::NAME,
35938 Self::AVAILABLE_MODES(..) => AVAILABLE_MODES_DATA::NAME,
35939 Self::AVAILABLE_MODES_MONITOR(..) => AVAILABLE_MODES_MONITOR_DATA::NAME,
35940 Self::BATTERY_INFO(..) => BATTERY_INFO_DATA::NAME,
35941 Self::BATTERY_STATUS(..) => BATTERY_STATUS_DATA::NAME,
35942 Self::BUTTON_CHANGE(..) => BUTTON_CHANGE_DATA::NAME,
35943 Self::CAMERA_CAPTURE_STATUS(..) => CAMERA_CAPTURE_STATUS_DATA::NAME,
35944 Self::CAMERA_FOV_STATUS(..) => CAMERA_FOV_STATUS_DATA::NAME,
35945 Self::CAMERA_IMAGE_CAPTURED(..) => CAMERA_IMAGE_CAPTURED_DATA::NAME,
35946 Self::CAMERA_INFORMATION(..) => CAMERA_INFORMATION_DATA::NAME,
35947 Self::CAMERA_SETTINGS(..) => CAMERA_SETTINGS_DATA::NAME,
35948 Self::CAMERA_THERMAL_RANGE(..) => CAMERA_THERMAL_RANGE_DATA::NAME,
35949 Self::CAMERA_TRACKING_GEO_STATUS(..) => CAMERA_TRACKING_GEO_STATUS_DATA::NAME,
35950 Self::CAMERA_TRACKING_IMAGE_STATUS(..) => CAMERA_TRACKING_IMAGE_STATUS_DATA::NAME,
35951 Self::CAMERA_TRIGGER(..) => CAMERA_TRIGGER_DATA::NAME,
35952 Self::CANFD_FRAME(..) => CANFD_FRAME_DATA::NAME,
35953 Self::CAN_FILTER_MODIFY(..) => CAN_FILTER_MODIFY_DATA::NAME,
35954 Self::CAN_FRAME(..) => CAN_FRAME_DATA::NAME,
35955 Self::CELLULAR_CONFIG(..) => CELLULAR_CONFIG_DATA::NAME,
35956 Self::CELLULAR_STATUS(..) => CELLULAR_STATUS_DATA::NAME,
35957 Self::CHANGE_OPERATOR_CONTROL(..) => CHANGE_OPERATOR_CONTROL_DATA::NAME,
35958 Self::CHANGE_OPERATOR_CONTROL_ACK(..) => CHANGE_OPERATOR_CONTROL_ACK_DATA::NAME,
35959 Self::COLLISION(..) => COLLISION_DATA::NAME,
35960 Self::COMMAND_ACK(..) => COMMAND_ACK_DATA::NAME,
35961 Self::COMMAND_CANCEL(..) => COMMAND_CANCEL_DATA::NAME,
35962 Self::COMMAND_INT(..) => COMMAND_INT_DATA::NAME,
35963 Self::COMMAND_LONG(..) => COMMAND_LONG_DATA::NAME,
35964 Self::COMPONENT_INFORMATION(..) => COMPONENT_INFORMATION_DATA::NAME,
35965 Self::COMPONENT_INFORMATION_BASIC(..) => COMPONENT_INFORMATION_BASIC_DATA::NAME,
35966 Self::COMPONENT_METADATA(..) => COMPONENT_METADATA_DATA::NAME,
35967 Self::CONTROL_SYSTEM_STATE(..) => CONTROL_SYSTEM_STATE_DATA::NAME,
35968 Self::CURRENT_EVENT_SEQUENCE(..) => CURRENT_EVENT_SEQUENCE_DATA::NAME,
35969 Self::CURRENT_MODE(..) => CURRENT_MODE_DATA::NAME,
35970 Self::DATA_STREAM(..) => DATA_STREAM_DATA::NAME,
35971 Self::DATA_TRANSMISSION_HANDSHAKE(..) => DATA_TRANSMISSION_HANDSHAKE_DATA::NAME,
35972 Self::DEBUG(..) => DEBUG_DATA::NAME,
35973 Self::DEBUG_FLOAT_ARRAY(..) => DEBUG_FLOAT_ARRAY_DATA::NAME,
35974 Self::DEBUG_VECT(..) => DEBUG_VECT_DATA::NAME,
35975 Self::DISTANCE_SENSOR(..) => DISTANCE_SENSOR_DATA::NAME,
35976 Self::EFI_STATUS(..) => EFI_STATUS_DATA::NAME,
35977 Self::ENCAPSULATED_DATA(..) => ENCAPSULATED_DATA_DATA::NAME,
35978 Self::ESC_INFO(..) => ESC_INFO_DATA::NAME,
35979 Self::ESC_STATUS(..) => ESC_STATUS_DATA::NAME,
35980 Self::ESTIMATOR_STATUS(..) => ESTIMATOR_STATUS_DATA::NAME,
35981 Self::EVENT(..) => EVENT_DATA::NAME,
35982 Self::EXTENDED_SYS_STATE(..) => EXTENDED_SYS_STATE_DATA::NAME,
35983 Self::FENCE_STATUS(..) => FENCE_STATUS_DATA::NAME,
35984 Self::FILE_TRANSFER_PROTOCOL(..) => FILE_TRANSFER_PROTOCOL_DATA::NAME,
35985 Self::FLIGHT_INFORMATION(..) => FLIGHT_INFORMATION_DATA::NAME,
35986 Self::FOLLOW_TARGET(..) => FOLLOW_TARGET_DATA::NAME,
35987 Self::FUEL_STATUS(..) => FUEL_STATUS_DATA::NAME,
35988 Self::GENERATOR_STATUS(..) => GENERATOR_STATUS_DATA::NAME,
35989 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(..) => GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::NAME,
35990 Self::GIMBAL_DEVICE_INFORMATION(..) => GIMBAL_DEVICE_INFORMATION_DATA::NAME,
35991 Self::GIMBAL_DEVICE_SET_ATTITUDE(..) => GIMBAL_DEVICE_SET_ATTITUDE_DATA::NAME,
35992 Self::GIMBAL_MANAGER_INFORMATION(..) => GIMBAL_MANAGER_INFORMATION_DATA::NAME,
35993 Self::GIMBAL_MANAGER_SET_ATTITUDE(..) => GIMBAL_MANAGER_SET_ATTITUDE_DATA::NAME,
35994 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(..) => {
35995 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::NAME
35996 }
35997 Self::GIMBAL_MANAGER_SET_PITCHYAW(..) => GIMBAL_MANAGER_SET_PITCHYAW_DATA::NAME,
35998 Self::GIMBAL_MANAGER_STATUS(..) => GIMBAL_MANAGER_STATUS_DATA::NAME,
35999 Self::GLOBAL_POSITION_INT(..) => GLOBAL_POSITION_INT_DATA::NAME,
36000 Self::GLOBAL_POSITION_INT_COV(..) => GLOBAL_POSITION_INT_COV_DATA::NAME,
36001 Self::GLOBAL_VISION_POSITION_ESTIMATE(..) => GLOBAL_VISION_POSITION_ESTIMATE_DATA::NAME,
36002 Self::GPS2_RAW(..) => GPS2_RAW_DATA::NAME,
36003 Self::GPS2_RTK(..) => GPS2_RTK_DATA::NAME,
36004 Self::GPS_GLOBAL_ORIGIN(..) => GPS_GLOBAL_ORIGIN_DATA::NAME,
36005 Self::GPS_INJECT_DATA(..) => GPS_INJECT_DATA_DATA::NAME,
36006 Self::GPS_INPUT(..) => GPS_INPUT_DATA::NAME,
36007 Self::GPS_RAW_INT(..) => GPS_RAW_INT_DATA::NAME,
36008 Self::GPS_RTCM_DATA(..) => GPS_RTCM_DATA_DATA::NAME,
36009 Self::GPS_RTK(..) => GPS_RTK_DATA::NAME,
36010 Self::GPS_STATUS(..) => GPS_STATUS_DATA::NAME,
36011 Self::HEARTBEAT(..) => HEARTBEAT_DATA::NAME,
36012 Self::HIGHRES_IMU(..) => HIGHRES_IMU_DATA::NAME,
36013 Self::HIGH_LATENCY(..) => HIGH_LATENCY_DATA::NAME,
36014 Self::HIGH_LATENCY2(..) => HIGH_LATENCY2_DATA::NAME,
36015 Self::HIL_ACTUATOR_CONTROLS(..) => HIL_ACTUATOR_CONTROLS_DATA::NAME,
36016 Self::HIL_CONTROLS(..) => HIL_CONTROLS_DATA::NAME,
36017 Self::HIL_GPS(..) => HIL_GPS_DATA::NAME,
36018 Self::HIL_OPTICAL_FLOW(..) => HIL_OPTICAL_FLOW_DATA::NAME,
36019 Self::HIL_RC_INPUTS_RAW(..) => HIL_RC_INPUTS_RAW_DATA::NAME,
36020 Self::HIL_SENSOR(..) => HIL_SENSOR_DATA::NAME,
36021 Self::HIL_STATE(..) => HIL_STATE_DATA::NAME,
36022 Self::HIL_STATE_QUATERNION(..) => HIL_STATE_QUATERNION_DATA::NAME,
36023 Self::HOME_POSITION(..) => HOME_POSITION_DATA::NAME,
36024 Self::HYGROMETER_SENSOR(..) => HYGROMETER_SENSOR_DATA::NAME,
36025 Self::ILLUMINATOR_STATUS(..) => ILLUMINATOR_STATUS_DATA::NAME,
36026 Self::ISBD_LINK_STATUS(..) => ISBD_LINK_STATUS_DATA::NAME,
36027 Self::LANDING_TARGET(..) => LANDING_TARGET_DATA::NAME,
36028 Self::LINK_NODE_STATUS(..) => LINK_NODE_STATUS_DATA::NAME,
36029 Self::LOCAL_POSITION_NED(..) => LOCAL_POSITION_NED_DATA::NAME,
36030 Self::LOCAL_POSITION_NED_COV(..) => LOCAL_POSITION_NED_COV_DATA::NAME,
36031 Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(..) => {
36032 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::NAME
36033 }
36034 Self::LOGGING_ACK(..) => LOGGING_ACK_DATA::NAME,
36035 Self::LOGGING_DATA(..) => LOGGING_DATA_DATA::NAME,
36036 Self::LOGGING_DATA_ACKED(..) => LOGGING_DATA_ACKED_DATA::NAME,
36037 Self::LOG_DATA(..) => LOG_DATA_DATA::NAME,
36038 Self::LOG_ENTRY(..) => LOG_ENTRY_DATA::NAME,
36039 Self::LOG_ERASE(..) => LOG_ERASE_DATA::NAME,
36040 Self::LOG_REQUEST_DATA(..) => LOG_REQUEST_DATA_DATA::NAME,
36041 Self::LOG_REQUEST_END(..) => LOG_REQUEST_END_DATA::NAME,
36042 Self::LOG_REQUEST_LIST(..) => LOG_REQUEST_LIST_DATA::NAME,
36043 Self::MAG_CAL_REPORT(..) => MAG_CAL_REPORT_DATA::NAME,
36044 Self::MANUAL_CONTROL(..) => MANUAL_CONTROL_DATA::NAME,
36045 Self::MANUAL_SETPOINT(..) => MANUAL_SETPOINT_DATA::NAME,
36046 Self::MEMORY_VECT(..) => MEMORY_VECT_DATA::NAME,
36047 Self::MESSAGE_INTERVAL(..) => MESSAGE_INTERVAL_DATA::NAME,
36048 Self::MISSION_ACK(..) => MISSION_ACK_DATA::NAME,
36049 Self::MISSION_CLEAR_ALL(..) => MISSION_CLEAR_ALL_DATA::NAME,
36050 Self::MISSION_COUNT(..) => MISSION_COUNT_DATA::NAME,
36051 Self::MISSION_CURRENT(..) => MISSION_CURRENT_DATA::NAME,
36052 Self::MISSION_ITEM(..) => MISSION_ITEM_DATA::NAME,
36053 Self::MISSION_ITEM_INT(..) => MISSION_ITEM_INT_DATA::NAME,
36054 Self::MISSION_ITEM_REACHED(..) => MISSION_ITEM_REACHED_DATA::NAME,
36055 Self::MISSION_REQUEST(..) => MISSION_REQUEST_DATA::NAME,
36056 Self::MISSION_REQUEST_INT(..) => MISSION_REQUEST_INT_DATA::NAME,
36057 Self::MISSION_REQUEST_LIST(..) => MISSION_REQUEST_LIST_DATA::NAME,
36058 Self::MISSION_REQUEST_PARTIAL_LIST(..) => MISSION_REQUEST_PARTIAL_LIST_DATA::NAME,
36059 Self::MISSION_SET_CURRENT(..) => MISSION_SET_CURRENT_DATA::NAME,
36060 Self::MISSION_WRITE_PARTIAL_LIST(..) => MISSION_WRITE_PARTIAL_LIST_DATA::NAME,
36061 Self::MOUNT_ORIENTATION(..) => MOUNT_ORIENTATION_DATA::NAME,
36062 Self::NAMED_VALUE_FLOAT(..) => NAMED_VALUE_FLOAT_DATA::NAME,
36063 Self::NAMED_VALUE_INT(..) => NAMED_VALUE_INT_DATA::NAME,
36064 Self::NAV_CONTROLLER_OUTPUT(..) => NAV_CONTROLLER_OUTPUT_DATA::NAME,
36065 Self::OBSTACLE_DISTANCE(..) => OBSTACLE_DISTANCE_DATA::NAME,
36066 Self::ODOMETRY(..) => ODOMETRY_DATA::NAME,
36067 Self::ONBOARD_COMPUTER_STATUS(..) => ONBOARD_COMPUTER_STATUS_DATA::NAME,
36068 Self::OPEN_DRONE_ID_ARM_STATUS(..) => OPEN_DRONE_ID_ARM_STATUS_DATA::NAME,
36069 Self::OPEN_DRONE_ID_AUTHENTICATION(..) => OPEN_DRONE_ID_AUTHENTICATION_DATA::NAME,
36070 Self::OPEN_DRONE_ID_BASIC_ID(..) => OPEN_DRONE_ID_BASIC_ID_DATA::NAME,
36071 Self::OPEN_DRONE_ID_LOCATION(..) => OPEN_DRONE_ID_LOCATION_DATA::NAME,
36072 Self::OPEN_DRONE_ID_MESSAGE_PACK(..) => OPEN_DRONE_ID_MESSAGE_PACK_DATA::NAME,
36073 Self::OPEN_DRONE_ID_OPERATOR_ID(..) => OPEN_DRONE_ID_OPERATOR_ID_DATA::NAME,
36074 Self::OPEN_DRONE_ID_SELF_ID(..) => OPEN_DRONE_ID_SELF_ID_DATA::NAME,
36075 Self::OPEN_DRONE_ID_SYSTEM(..) => OPEN_DRONE_ID_SYSTEM_DATA::NAME,
36076 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(..) => OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::NAME,
36077 Self::OPTICAL_FLOW(..) => OPTICAL_FLOW_DATA::NAME,
36078 Self::OPTICAL_FLOW_RAD(..) => OPTICAL_FLOW_RAD_DATA::NAME,
36079 Self::ORBIT_EXECUTION_STATUS(..) => ORBIT_EXECUTION_STATUS_DATA::NAME,
36080 Self::PARAM_EXT_ACK(..) => PARAM_EXT_ACK_DATA::NAME,
36081 Self::PARAM_EXT_REQUEST_LIST(..) => PARAM_EXT_REQUEST_LIST_DATA::NAME,
36082 Self::PARAM_EXT_REQUEST_READ(..) => PARAM_EXT_REQUEST_READ_DATA::NAME,
36083 Self::PARAM_EXT_SET(..) => PARAM_EXT_SET_DATA::NAME,
36084 Self::PARAM_EXT_VALUE(..) => PARAM_EXT_VALUE_DATA::NAME,
36085 Self::PARAM_MAP_RC(..) => PARAM_MAP_RC_DATA::NAME,
36086 Self::PARAM_REQUEST_LIST(..) => PARAM_REQUEST_LIST_DATA::NAME,
36087 Self::PARAM_REQUEST_READ(..) => PARAM_REQUEST_READ_DATA::NAME,
36088 Self::PARAM_SET(..) => PARAM_SET_DATA::NAME,
36089 Self::PARAM_VALUE(..) => PARAM_VALUE_DATA::NAME,
36090 Self::PING(..) => PING_DATA::NAME,
36091 Self::PLAY_TUNE(..) => PLAY_TUNE_DATA::NAME,
36092 Self::PLAY_TUNE_V2(..) => PLAY_TUNE_V2_DATA::NAME,
36093 Self::POSITION_TARGET_GLOBAL_INT(..) => POSITION_TARGET_GLOBAL_INT_DATA::NAME,
36094 Self::POSITION_TARGET_LOCAL_NED(..) => POSITION_TARGET_LOCAL_NED_DATA::NAME,
36095 Self::POWER_STATUS(..) => POWER_STATUS_DATA::NAME,
36096 Self::PROTOCOL_VERSION(..) => PROTOCOL_VERSION_DATA::NAME,
36097 Self::RADIO_STATUS(..) => RADIO_STATUS_DATA::NAME,
36098 Self::RAW_IMU(..) => RAW_IMU_DATA::NAME,
36099 Self::RAW_PRESSURE(..) => RAW_PRESSURE_DATA::NAME,
36100 Self::RAW_RPM(..) => RAW_RPM_DATA::NAME,
36101 Self::RC_CHANNELS(..) => RC_CHANNELS_DATA::NAME,
36102 Self::RC_CHANNELS_OVERRIDE(..) => RC_CHANNELS_OVERRIDE_DATA::NAME,
36103 Self::RC_CHANNELS_RAW(..) => RC_CHANNELS_RAW_DATA::NAME,
36104 Self::RC_CHANNELS_SCALED(..) => RC_CHANNELS_SCALED_DATA::NAME,
36105 Self::REQUEST_DATA_STREAM(..) => REQUEST_DATA_STREAM_DATA::NAME,
36106 Self::REQUEST_EVENT(..) => REQUEST_EVENT_DATA::NAME,
36107 Self::RESOURCE_REQUEST(..) => RESOURCE_REQUEST_DATA::NAME,
36108 Self::RESPONSE_EVENT_ERROR(..) => RESPONSE_EVENT_ERROR_DATA::NAME,
36109 Self::SAFETY_ALLOWED_AREA(..) => SAFETY_ALLOWED_AREA_DATA::NAME,
36110 Self::SAFETY_SET_ALLOWED_AREA(..) => SAFETY_SET_ALLOWED_AREA_DATA::NAME,
36111 Self::SCALED_IMU(..) => SCALED_IMU_DATA::NAME,
36112 Self::SCALED_IMU2(..) => SCALED_IMU2_DATA::NAME,
36113 Self::SCALED_IMU3(..) => SCALED_IMU3_DATA::NAME,
36114 Self::SCALED_PRESSURE(..) => SCALED_PRESSURE_DATA::NAME,
36115 Self::SCALED_PRESSURE2(..) => SCALED_PRESSURE2_DATA::NAME,
36116 Self::SCALED_PRESSURE3(..) => SCALED_PRESSURE3_DATA::NAME,
36117 Self::SERIAL_CONTROL(..) => SERIAL_CONTROL_DATA::NAME,
36118 Self::SERVO_OUTPUT_RAW(..) => SERVO_OUTPUT_RAW_DATA::NAME,
36119 Self::SETUP_SIGNING(..) => SETUP_SIGNING_DATA::NAME,
36120 Self::SET_ACTUATOR_CONTROL_TARGET(..) => SET_ACTUATOR_CONTROL_TARGET_DATA::NAME,
36121 Self::SET_ATTITUDE_TARGET(..) => SET_ATTITUDE_TARGET_DATA::NAME,
36122 Self::SET_GPS_GLOBAL_ORIGIN(..) => SET_GPS_GLOBAL_ORIGIN_DATA::NAME,
36123 Self::SET_HOME_POSITION(..) => SET_HOME_POSITION_DATA::NAME,
36124 Self::SET_MODE(..) => SET_MODE_DATA::NAME,
36125 Self::SET_POSITION_TARGET_GLOBAL_INT(..) => SET_POSITION_TARGET_GLOBAL_INT_DATA::NAME,
36126 Self::SET_POSITION_TARGET_LOCAL_NED(..) => SET_POSITION_TARGET_LOCAL_NED_DATA::NAME,
36127 Self::SIM_STATE(..) => SIM_STATE_DATA::NAME,
36128 Self::SMART_BATTERY_INFO(..) => SMART_BATTERY_INFO_DATA::NAME,
36129 Self::STATUSTEXT(..) => STATUSTEXT_DATA::NAME,
36130 Self::STORAGE_INFORMATION(..) => STORAGE_INFORMATION_DATA::NAME,
36131 Self::SUPPORTED_TUNES(..) => SUPPORTED_TUNES_DATA::NAME,
36132 Self::SYSTEM_TIME(..) => SYSTEM_TIME_DATA::NAME,
36133 Self::SYS_STATUS(..) => SYS_STATUS_DATA::NAME,
36134 Self::TERRAIN_CHECK(..) => TERRAIN_CHECK_DATA::NAME,
36135 Self::TERRAIN_DATA(..) => TERRAIN_DATA_DATA::NAME,
36136 Self::TERRAIN_REPORT(..) => TERRAIN_REPORT_DATA::NAME,
36137 Self::TERRAIN_REQUEST(..) => TERRAIN_REQUEST_DATA::NAME,
36138 Self::TIMESYNC(..) => TIMESYNC_DATA::NAME,
36139 Self::TIME_ESTIMATE_TO_TARGET(..) => TIME_ESTIMATE_TO_TARGET_DATA::NAME,
36140 Self::TRAJECTORY_REPRESENTATION_BEZIER(..) => {
36141 TRAJECTORY_REPRESENTATION_BEZIER_DATA::NAME
36142 }
36143 Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(..) => {
36144 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::NAME
36145 }
36146 Self::TUNNEL(..) => TUNNEL_DATA::NAME,
36147 Self::UAVCAN_NODE_INFO(..) => UAVCAN_NODE_INFO_DATA::NAME,
36148 Self::UAVCAN_NODE_STATUS(..) => UAVCAN_NODE_STATUS_DATA::NAME,
36149 Self::UTM_GLOBAL_POSITION(..) => UTM_GLOBAL_POSITION_DATA::NAME,
36150 Self::V2_EXTENSION(..) => V2_EXTENSION_DATA::NAME,
36151 Self::VFR_HUD(..) => VFR_HUD_DATA::NAME,
36152 Self::VIBRATION(..) => VIBRATION_DATA::NAME,
36153 Self::VICON_POSITION_ESTIMATE(..) => VICON_POSITION_ESTIMATE_DATA::NAME,
36154 Self::VIDEO_STREAM_INFORMATION(..) => VIDEO_STREAM_INFORMATION_DATA::NAME,
36155 Self::VIDEO_STREAM_STATUS(..) => VIDEO_STREAM_STATUS_DATA::NAME,
36156 Self::VISION_POSITION_ESTIMATE(..) => VISION_POSITION_ESTIMATE_DATA::NAME,
36157 Self::VISION_SPEED_ESTIMATE(..) => VISION_SPEED_ESTIMATE_DATA::NAME,
36158 Self::WHEEL_DISTANCE(..) => WHEEL_DISTANCE_DATA::NAME,
36159 Self::WIFI_CONFIG_AP(..) => WIFI_CONFIG_AP_DATA::NAME,
36160 Self::WINCH_STATUS(..) => WINCH_STATUS_DATA::NAME,
36161 Self::WIND_COV(..) => WIND_COV_DATA::NAME,
36162 }
36163 }
36164 fn message_id(&self) -> u32 {
36165 match self {
36166 Self::ACTUATOR_CONTROL_TARGET(..) => ACTUATOR_CONTROL_TARGET_DATA::ID,
36167 Self::ACTUATOR_OUTPUT_STATUS(..) => ACTUATOR_OUTPUT_STATUS_DATA::ID,
36168 Self::ADSB_VEHICLE(..) => ADSB_VEHICLE_DATA::ID,
36169 Self::AIS_VESSEL(..) => AIS_VESSEL_DATA::ID,
36170 Self::ALTITUDE(..) => ALTITUDE_DATA::ID,
36171 Self::ATTITUDE(..) => ATTITUDE_DATA::ID,
36172 Self::ATTITUDE_QUATERNION(..) => ATTITUDE_QUATERNION_DATA::ID,
36173 Self::ATTITUDE_QUATERNION_COV(..) => ATTITUDE_QUATERNION_COV_DATA::ID,
36174 Self::ATTITUDE_TARGET(..) => ATTITUDE_TARGET_DATA::ID,
36175 Self::ATT_POS_MOCAP(..) => ATT_POS_MOCAP_DATA::ID,
36176 Self::AUTH_KEY(..) => AUTH_KEY_DATA::ID,
36177 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(..) => {
36178 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID
36179 }
36180 Self::AUTOPILOT_VERSION(..) => AUTOPILOT_VERSION_DATA::ID,
36181 Self::AVAILABLE_MODES(..) => AVAILABLE_MODES_DATA::ID,
36182 Self::AVAILABLE_MODES_MONITOR(..) => AVAILABLE_MODES_MONITOR_DATA::ID,
36183 Self::BATTERY_INFO(..) => BATTERY_INFO_DATA::ID,
36184 Self::BATTERY_STATUS(..) => BATTERY_STATUS_DATA::ID,
36185 Self::BUTTON_CHANGE(..) => BUTTON_CHANGE_DATA::ID,
36186 Self::CAMERA_CAPTURE_STATUS(..) => CAMERA_CAPTURE_STATUS_DATA::ID,
36187 Self::CAMERA_FOV_STATUS(..) => CAMERA_FOV_STATUS_DATA::ID,
36188 Self::CAMERA_IMAGE_CAPTURED(..) => CAMERA_IMAGE_CAPTURED_DATA::ID,
36189 Self::CAMERA_INFORMATION(..) => CAMERA_INFORMATION_DATA::ID,
36190 Self::CAMERA_SETTINGS(..) => CAMERA_SETTINGS_DATA::ID,
36191 Self::CAMERA_THERMAL_RANGE(..) => CAMERA_THERMAL_RANGE_DATA::ID,
36192 Self::CAMERA_TRACKING_GEO_STATUS(..) => CAMERA_TRACKING_GEO_STATUS_DATA::ID,
36193 Self::CAMERA_TRACKING_IMAGE_STATUS(..) => CAMERA_TRACKING_IMAGE_STATUS_DATA::ID,
36194 Self::CAMERA_TRIGGER(..) => CAMERA_TRIGGER_DATA::ID,
36195 Self::CANFD_FRAME(..) => CANFD_FRAME_DATA::ID,
36196 Self::CAN_FILTER_MODIFY(..) => CAN_FILTER_MODIFY_DATA::ID,
36197 Self::CAN_FRAME(..) => CAN_FRAME_DATA::ID,
36198 Self::CELLULAR_CONFIG(..) => CELLULAR_CONFIG_DATA::ID,
36199 Self::CELLULAR_STATUS(..) => CELLULAR_STATUS_DATA::ID,
36200 Self::CHANGE_OPERATOR_CONTROL(..) => CHANGE_OPERATOR_CONTROL_DATA::ID,
36201 Self::CHANGE_OPERATOR_CONTROL_ACK(..) => CHANGE_OPERATOR_CONTROL_ACK_DATA::ID,
36202 Self::COLLISION(..) => COLLISION_DATA::ID,
36203 Self::COMMAND_ACK(..) => COMMAND_ACK_DATA::ID,
36204 Self::COMMAND_CANCEL(..) => COMMAND_CANCEL_DATA::ID,
36205 Self::COMMAND_INT(..) => COMMAND_INT_DATA::ID,
36206 Self::COMMAND_LONG(..) => COMMAND_LONG_DATA::ID,
36207 Self::COMPONENT_INFORMATION(..) => COMPONENT_INFORMATION_DATA::ID,
36208 Self::COMPONENT_INFORMATION_BASIC(..) => COMPONENT_INFORMATION_BASIC_DATA::ID,
36209 Self::COMPONENT_METADATA(..) => COMPONENT_METADATA_DATA::ID,
36210 Self::CONTROL_SYSTEM_STATE(..) => CONTROL_SYSTEM_STATE_DATA::ID,
36211 Self::CURRENT_EVENT_SEQUENCE(..) => CURRENT_EVENT_SEQUENCE_DATA::ID,
36212 Self::CURRENT_MODE(..) => CURRENT_MODE_DATA::ID,
36213 Self::DATA_STREAM(..) => DATA_STREAM_DATA::ID,
36214 Self::DATA_TRANSMISSION_HANDSHAKE(..) => DATA_TRANSMISSION_HANDSHAKE_DATA::ID,
36215 Self::DEBUG(..) => DEBUG_DATA::ID,
36216 Self::DEBUG_FLOAT_ARRAY(..) => DEBUG_FLOAT_ARRAY_DATA::ID,
36217 Self::DEBUG_VECT(..) => DEBUG_VECT_DATA::ID,
36218 Self::DISTANCE_SENSOR(..) => DISTANCE_SENSOR_DATA::ID,
36219 Self::EFI_STATUS(..) => EFI_STATUS_DATA::ID,
36220 Self::ENCAPSULATED_DATA(..) => ENCAPSULATED_DATA_DATA::ID,
36221 Self::ESC_INFO(..) => ESC_INFO_DATA::ID,
36222 Self::ESC_STATUS(..) => ESC_STATUS_DATA::ID,
36223 Self::ESTIMATOR_STATUS(..) => ESTIMATOR_STATUS_DATA::ID,
36224 Self::EVENT(..) => EVENT_DATA::ID,
36225 Self::EXTENDED_SYS_STATE(..) => EXTENDED_SYS_STATE_DATA::ID,
36226 Self::FENCE_STATUS(..) => FENCE_STATUS_DATA::ID,
36227 Self::FILE_TRANSFER_PROTOCOL(..) => FILE_TRANSFER_PROTOCOL_DATA::ID,
36228 Self::FLIGHT_INFORMATION(..) => FLIGHT_INFORMATION_DATA::ID,
36229 Self::FOLLOW_TARGET(..) => FOLLOW_TARGET_DATA::ID,
36230 Self::FUEL_STATUS(..) => FUEL_STATUS_DATA::ID,
36231 Self::GENERATOR_STATUS(..) => GENERATOR_STATUS_DATA::ID,
36232 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(..) => GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID,
36233 Self::GIMBAL_DEVICE_INFORMATION(..) => GIMBAL_DEVICE_INFORMATION_DATA::ID,
36234 Self::GIMBAL_DEVICE_SET_ATTITUDE(..) => GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID,
36235 Self::GIMBAL_MANAGER_INFORMATION(..) => GIMBAL_MANAGER_INFORMATION_DATA::ID,
36236 Self::GIMBAL_MANAGER_SET_ATTITUDE(..) => GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID,
36237 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(..) => {
36238 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID
36239 }
36240 Self::GIMBAL_MANAGER_SET_PITCHYAW(..) => GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID,
36241 Self::GIMBAL_MANAGER_STATUS(..) => GIMBAL_MANAGER_STATUS_DATA::ID,
36242 Self::GLOBAL_POSITION_INT(..) => GLOBAL_POSITION_INT_DATA::ID,
36243 Self::GLOBAL_POSITION_INT_COV(..) => GLOBAL_POSITION_INT_COV_DATA::ID,
36244 Self::GLOBAL_VISION_POSITION_ESTIMATE(..) => GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID,
36245 Self::GPS2_RAW(..) => GPS2_RAW_DATA::ID,
36246 Self::GPS2_RTK(..) => GPS2_RTK_DATA::ID,
36247 Self::GPS_GLOBAL_ORIGIN(..) => GPS_GLOBAL_ORIGIN_DATA::ID,
36248 Self::GPS_INJECT_DATA(..) => GPS_INJECT_DATA_DATA::ID,
36249 Self::GPS_INPUT(..) => GPS_INPUT_DATA::ID,
36250 Self::GPS_RAW_INT(..) => GPS_RAW_INT_DATA::ID,
36251 Self::GPS_RTCM_DATA(..) => GPS_RTCM_DATA_DATA::ID,
36252 Self::GPS_RTK(..) => GPS_RTK_DATA::ID,
36253 Self::GPS_STATUS(..) => GPS_STATUS_DATA::ID,
36254 Self::HEARTBEAT(..) => HEARTBEAT_DATA::ID,
36255 Self::HIGHRES_IMU(..) => HIGHRES_IMU_DATA::ID,
36256 Self::HIGH_LATENCY(..) => HIGH_LATENCY_DATA::ID,
36257 Self::HIGH_LATENCY2(..) => HIGH_LATENCY2_DATA::ID,
36258 Self::HIL_ACTUATOR_CONTROLS(..) => HIL_ACTUATOR_CONTROLS_DATA::ID,
36259 Self::HIL_CONTROLS(..) => HIL_CONTROLS_DATA::ID,
36260 Self::HIL_GPS(..) => HIL_GPS_DATA::ID,
36261 Self::HIL_OPTICAL_FLOW(..) => HIL_OPTICAL_FLOW_DATA::ID,
36262 Self::HIL_RC_INPUTS_RAW(..) => HIL_RC_INPUTS_RAW_DATA::ID,
36263 Self::HIL_SENSOR(..) => HIL_SENSOR_DATA::ID,
36264 Self::HIL_STATE(..) => HIL_STATE_DATA::ID,
36265 Self::HIL_STATE_QUATERNION(..) => HIL_STATE_QUATERNION_DATA::ID,
36266 Self::HOME_POSITION(..) => HOME_POSITION_DATA::ID,
36267 Self::HYGROMETER_SENSOR(..) => HYGROMETER_SENSOR_DATA::ID,
36268 Self::ILLUMINATOR_STATUS(..) => ILLUMINATOR_STATUS_DATA::ID,
36269 Self::ISBD_LINK_STATUS(..) => ISBD_LINK_STATUS_DATA::ID,
36270 Self::LANDING_TARGET(..) => LANDING_TARGET_DATA::ID,
36271 Self::LINK_NODE_STATUS(..) => LINK_NODE_STATUS_DATA::ID,
36272 Self::LOCAL_POSITION_NED(..) => LOCAL_POSITION_NED_DATA::ID,
36273 Self::LOCAL_POSITION_NED_COV(..) => LOCAL_POSITION_NED_COV_DATA::ID,
36274 Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(..) => {
36275 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID
36276 }
36277 Self::LOGGING_ACK(..) => LOGGING_ACK_DATA::ID,
36278 Self::LOGGING_DATA(..) => LOGGING_DATA_DATA::ID,
36279 Self::LOGGING_DATA_ACKED(..) => LOGGING_DATA_ACKED_DATA::ID,
36280 Self::LOG_DATA(..) => LOG_DATA_DATA::ID,
36281 Self::LOG_ENTRY(..) => LOG_ENTRY_DATA::ID,
36282 Self::LOG_ERASE(..) => LOG_ERASE_DATA::ID,
36283 Self::LOG_REQUEST_DATA(..) => LOG_REQUEST_DATA_DATA::ID,
36284 Self::LOG_REQUEST_END(..) => LOG_REQUEST_END_DATA::ID,
36285 Self::LOG_REQUEST_LIST(..) => LOG_REQUEST_LIST_DATA::ID,
36286 Self::MAG_CAL_REPORT(..) => MAG_CAL_REPORT_DATA::ID,
36287 Self::MANUAL_CONTROL(..) => MANUAL_CONTROL_DATA::ID,
36288 Self::MANUAL_SETPOINT(..) => MANUAL_SETPOINT_DATA::ID,
36289 Self::MEMORY_VECT(..) => MEMORY_VECT_DATA::ID,
36290 Self::MESSAGE_INTERVAL(..) => MESSAGE_INTERVAL_DATA::ID,
36291 Self::MISSION_ACK(..) => MISSION_ACK_DATA::ID,
36292 Self::MISSION_CLEAR_ALL(..) => MISSION_CLEAR_ALL_DATA::ID,
36293 Self::MISSION_COUNT(..) => MISSION_COUNT_DATA::ID,
36294 Self::MISSION_CURRENT(..) => MISSION_CURRENT_DATA::ID,
36295 Self::MISSION_ITEM(..) => MISSION_ITEM_DATA::ID,
36296 Self::MISSION_ITEM_INT(..) => MISSION_ITEM_INT_DATA::ID,
36297 Self::MISSION_ITEM_REACHED(..) => MISSION_ITEM_REACHED_DATA::ID,
36298 Self::MISSION_REQUEST(..) => MISSION_REQUEST_DATA::ID,
36299 Self::MISSION_REQUEST_INT(..) => MISSION_REQUEST_INT_DATA::ID,
36300 Self::MISSION_REQUEST_LIST(..) => MISSION_REQUEST_LIST_DATA::ID,
36301 Self::MISSION_REQUEST_PARTIAL_LIST(..) => MISSION_REQUEST_PARTIAL_LIST_DATA::ID,
36302 Self::MISSION_SET_CURRENT(..) => MISSION_SET_CURRENT_DATA::ID,
36303 Self::MISSION_WRITE_PARTIAL_LIST(..) => MISSION_WRITE_PARTIAL_LIST_DATA::ID,
36304 Self::MOUNT_ORIENTATION(..) => MOUNT_ORIENTATION_DATA::ID,
36305 Self::NAMED_VALUE_FLOAT(..) => NAMED_VALUE_FLOAT_DATA::ID,
36306 Self::NAMED_VALUE_INT(..) => NAMED_VALUE_INT_DATA::ID,
36307 Self::NAV_CONTROLLER_OUTPUT(..) => NAV_CONTROLLER_OUTPUT_DATA::ID,
36308 Self::OBSTACLE_DISTANCE(..) => OBSTACLE_DISTANCE_DATA::ID,
36309 Self::ODOMETRY(..) => ODOMETRY_DATA::ID,
36310 Self::ONBOARD_COMPUTER_STATUS(..) => ONBOARD_COMPUTER_STATUS_DATA::ID,
36311 Self::OPEN_DRONE_ID_ARM_STATUS(..) => OPEN_DRONE_ID_ARM_STATUS_DATA::ID,
36312 Self::OPEN_DRONE_ID_AUTHENTICATION(..) => OPEN_DRONE_ID_AUTHENTICATION_DATA::ID,
36313 Self::OPEN_DRONE_ID_BASIC_ID(..) => OPEN_DRONE_ID_BASIC_ID_DATA::ID,
36314 Self::OPEN_DRONE_ID_LOCATION(..) => OPEN_DRONE_ID_LOCATION_DATA::ID,
36315 Self::OPEN_DRONE_ID_MESSAGE_PACK(..) => OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID,
36316 Self::OPEN_DRONE_ID_OPERATOR_ID(..) => OPEN_DRONE_ID_OPERATOR_ID_DATA::ID,
36317 Self::OPEN_DRONE_ID_SELF_ID(..) => OPEN_DRONE_ID_SELF_ID_DATA::ID,
36318 Self::OPEN_DRONE_ID_SYSTEM(..) => OPEN_DRONE_ID_SYSTEM_DATA::ID,
36319 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(..) => OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID,
36320 Self::OPTICAL_FLOW(..) => OPTICAL_FLOW_DATA::ID,
36321 Self::OPTICAL_FLOW_RAD(..) => OPTICAL_FLOW_RAD_DATA::ID,
36322 Self::ORBIT_EXECUTION_STATUS(..) => ORBIT_EXECUTION_STATUS_DATA::ID,
36323 Self::PARAM_EXT_ACK(..) => PARAM_EXT_ACK_DATA::ID,
36324 Self::PARAM_EXT_REQUEST_LIST(..) => PARAM_EXT_REQUEST_LIST_DATA::ID,
36325 Self::PARAM_EXT_REQUEST_READ(..) => PARAM_EXT_REQUEST_READ_DATA::ID,
36326 Self::PARAM_EXT_SET(..) => PARAM_EXT_SET_DATA::ID,
36327 Self::PARAM_EXT_VALUE(..) => PARAM_EXT_VALUE_DATA::ID,
36328 Self::PARAM_MAP_RC(..) => PARAM_MAP_RC_DATA::ID,
36329 Self::PARAM_REQUEST_LIST(..) => PARAM_REQUEST_LIST_DATA::ID,
36330 Self::PARAM_REQUEST_READ(..) => PARAM_REQUEST_READ_DATA::ID,
36331 Self::PARAM_SET(..) => PARAM_SET_DATA::ID,
36332 Self::PARAM_VALUE(..) => PARAM_VALUE_DATA::ID,
36333 Self::PING(..) => PING_DATA::ID,
36334 Self::PLAY_TUNE(..) => PLAY_TUNE_DATA::ID,
36335 Self::PLAY_TUNE_V2(..) => PLAY_TUNE_V2_DATA::ID,
36336 Self::POSITION_TARGET_GLOBAL_INT(..) => POSITION_TARGET_GLOBAL_INT_DATA::ID,
36337 Self::POSITION_TARGET_LOCAL_NED(..) => POSITION_TARGET_LOCAL_NED_DATA::ID,
36338 Self::POWER_STATUS(..) => POWER_STATUS_DATA::ID,
36339 Self::PROTOCOL_VERSION(..) => PROTOCOL_VERSION_DATA::ID,
36340 Self::RADIO_STATUS(..) => RADIO_STATUS_DATA::ID,
36341 Self::RAW_IMU(..) => RAW_IMU_DATA::ID,
36342 Self::RAW_PRESSURE(..) => RAW_PRESSURE_DATA::ID,
36343 Self::RAW_RPM(..) => RAW_RPM_DATA::ID,
36344 Self::RC_CHANNELS(..) => RC_CHANNELS_DATA::ID,
36345 Self::RC_CHANNELS_OVERRIDE(..) => RC_CHANNELS_OVERRIDE_DATA::ID,
36346 Self::RC_CHANNELS_RAW(..) => RC_CHANNELS_RAW_DATA::ID,
36347 Self::RC_CHANNELS_SCALED(..) => RC_CHANNELS_SCALED_DATA::ID,
36348 Self::REQUEST_DATA_STREAM(..) => REQUEST_DATA_STREAM_DATA::ID,
36349 Self::REQUEST_EVENT(..) => REQUEST_EVENT_DATA::ID,
36350 Self::RESOURCE_REQUEST(..) => RESOURCE_REQUEST_DATA::ID,
36351 Self::RESPONSE_EVENT_ERROR(..) => RESPONSE_EVENT_ERROR_DATA::ID,
36352 Self::SAFETY_ALLOWED_AREA(..) => SAFETY_ALLOWED_AREA_DATA::ID,
36353 Self::SAFETY_SET_ALLOWED_AREA(..) => SAFETY_SET_ALLOWED_AREA_DATA::ID,
36354 Self::SCALED_IMU(..) => SCALED_IMU_DATA::ID,
36355 Self::SCALED_IMU2(..) => SCALED_IMU2_DATA::ID,
36356 Self::SCALED_IMU3(..) => SCALED_IMU3_DATA::ID,
36357 Self::SCALED_PRESSURE(..) => SCALED_PRESSURE_DATA::ID,
36358 Self::SCALED_PRESSURE2(..) => SCALED_PRESSURE2_DATA::ID,
36359 Self::SCALED_PRESSURE3(..) => SCALED_PRESSURE3_DATA::ID,
36360 Self::SERIAL_CONTROL(..) => SERIAL_CONTROL_DATA::ID,
36361 Self::SERVO_OUTPUT_RAW(..) => SERVO_OUTPUT_RAW_DATA::ID,
36362 Self::SETUP_SIGNING(..) => SETUP_SIGNING_DATA::ID,
36363 Self::SET_ACTUATOR_CONTROL_TARGET(..) => SET_ACTUATOR_CONTROL_TARGET_DATA::ID,
36364 Self::SET_ATTITUDE_TARGET(..) => SET_ATTITUDE_TARGET_DATA::ID,
36365 Self::SET_GPS_GLOBAL_ORIGIN(..) => SET_GPS_GLOBAL_ORIGIN_DATA::ID,
36366 Self::SET_HOME_POSITION(..) => SET_HOME_POSITION_DATA::ID,
36367 Self::SET_MODE(..) => SET_MODE_DATA::ID,
36368 Self::SET_POSITION_TARGET_GLOBAL_INT(..) => SET_POSITION_TARGET_GLOBAL_INT_DATA::ID,
36369 Self::SET_POSITION_TARGET_LOCAL_NED(..) => SET_POSITION_TARGET_LOCAL_NED_DATA::ID,
36370 Self::SIM_STATE(..) => SIM_STATE_DATA::ID,
36371 Self::SMART_BATTERY_INFO(..) => SMART_BATTERY_INFO_DATA::ID,
36372 Self::STATUSTEXT(..) => STATUSTEXT_DATA::ID,
36373 Self::STORAGE_INFORMATION(..) => STORAGE_INFORMATION_DATA::ID,
36374 Self::SUPPORTED_TUNES(..) => SUPPORTED_TUNES_DATA::ID,
36375 Self::SYSTEM_TIME(..) => SYSTEM_TIME_DATA::ID,
36376 Self::SYS_STATUS(..) => SYS_STATUS_DATA::ID,
36377 Self::TERRAIN_CHECK(..) => TERRAIN_CHECK_DATA::ID,
36378 Self::TERRAIN_DATA(..) => TERRAIN_DATA_DATA::ID,
36379 Self::TERRAIN_REPORT(..) => TERRAIN_REPORT_DATA::ID,
36380 Self::TERRAIN_REQUEST(..) => TERRAIN_REQUEST_DATA::ID,
36381 Self::TIMESYNC(..) => TIMESYNC_DATA::ID,
36382 Self::TIME_ESTIMATE_TO_TARGET(..) => TIME_ESTIMATE_TO_TARGET_DATA::ID,
36383 Self::TRAJECTORY_REPRESENTATION_BEZIER(..) => TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID,
36384 Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(..) => {
36385 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID
36386 }
36387 Self::TUNNEL(..) => TUNNEL_DATA::ID,
36388 Self::UAVCAN_NODE_INFO(..) => UAVCAN_NODE_INFO_DATA::ID,
36389 Self::UAVCAN_NODE_STATUS(..) => UAVCAN_NODE_STATUS_DATA::ID,
36390 Self::UTM_GLOBAL_POSITION(..) => UTM_GLOBAL_POSITION_DATA::ID,
36391 Self::V2_EXTENSION(..) => V2_EXTENSION_DATA::ID,
36392 Self::VFR_HUD(..) => VFR_HUD_DATA::ID,
36393 Self::VIBRATION(..) => VIBRATION_DATA::ID,
36394 Self::VICON_POSITION_ESTIMATE(..) => VICON_POSITION_ESTIMATE_DATA::ID,
36395 Self::VIDEO_STREAM_INFORMATION(..) => VIDEO_STREAM_INFORMATION_DATA::ID,
36396 Self::VIDEO_STREAM_STATUS(..) => VIDEO_STREAM_STATUS_DATA::ID,
36397 Self::VISION_POSITION_ESTIMATE(..) => VISION_POSITION_ESTIMATE_DATA::ID,
36398 Self::VISION_SPEED_ESTIMATE(..) => VISION_SPEED_ESTIMATE_DATA::ID,
36399 Self::WHEEL_DISTANCE(..) => WHEEL_DISTANCE_DATA::ID,
36400 Self::WIFI_CONFIG_AP(..) => WIFI_CONFIG_AP_DATA::ID,
36401 Self::WINCH_STATUS(..) => WINCH_STATUS_DATA::ID,
36402 Self::WIND_COV(..) => WIND_COV_DATA::ID,
36403 }
36404 }
36405 fn message_id_from_name(name: &str) -> Option<u32> {
36406 match name {
36407 ACTUATOR_CONTROL_TARGET_DATA::NAME => Some(ACTUATOR_CONTROL_TARGET_DATA::ID),
36408 ACTUATOR_OUTPUT_STATUS_DATA::NAME => Some(ACTUATOR_OUTPUT_STATUS_DATA::ID),
36409 ADSB_VEHICLE_DATA::NAME => Some(ADSB_VEHICLE_DATA::ID),
36410 AIS_VESSEL_DATA::NAME => Some(AIS_VESSEL_DATA::ID),
36411 ALTITUDE_DATA::NAME => Some(ALTITUDE_DATA::ID),
36412 ATTITUDE_DATA::NAME => Some(ATTITUDE_DATA::ID),
36413 ATTITUDE_QUATERNION_DATA::NAME => Some(ATTITUDE_QUATERNION_DATA::ID),
36414 ATTITUDE_QUATERNION_COV_DATA::NAME => Some(ATTITUDE_QUATERNION_COV_DATA::ID),
36415 ATTITUDE_TARGET_DATA::NAME => Some(ATTITUDE_TARGET_DATA::ID),
36416 ATT_POS_MOCAP_DATA::NAME => Some(ATT_POS_MOCAP_DATA::ID),
36417 AUTH_KEY_DATA::NAME => Some(AUTH_KEY_DATA::ID),
36418 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::NAME => {
36419 Some(AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID)
36420 }
36421 AUTOPILOT_VERSION_DATA::NAME => Some(AUTOPILOT_VERSION_DATA::ID),
36422 AVAILABLE_MODES_DATA::NAME => Some(AVAILABLE_MODES_DATA::ID),
36423 AVAILABLE_MODES_MONITOR_DATA::NAME => Some(AVAILABLE_MODES_MONITOR_DATA::ID),
36424 BATTERY_INFO_DATA::NAME => Some(BATTERY_INFO_DATA::ID),
36425 BATTERY_STATUS_DATA::NAME => Some(BATTERY_STATUS_DATA::ID),
36426 BUTTON_CHANGE_DATA::NAME => Some(BUTTON_CHANGE_DATA::ID),
36427 CAMERA_CAPTURE_STATUS_DATA::NAME => Some(CAMERA_CAPTURE_STATUS_DATA::ID),
36428 CAMERA_FOV_STATUS_DATA::NAME => Some(CAMERA_FOV_STATUS_DATA::ID),
36429 CAMERA_IMAGE_CAPTURED_DATA::NAME => Some(CAMERA_IMAGE_CAPTURED_DATA::ID),
36430 CAMERA_INFORMATION_DATA::NAME => Some(CAMERA_INFORMATION_DATA::ID),
36431 CAMERA_SETTINGS_DATA::NAME => Some(CAMERA_SETTINGS_DATA::ID),
36432 CAMERA_THERMAL_RANGE_DATA::NAME => Some(CAMERA_THERMAL_RANGE_DATA::ID),
36433 CAMERA_TRACKING_GEO_STATUS_DATA::NAME => Some(CAMERA_TRACKING_GEO_STATUS_DATA::ID),
36434 CAMERA_TRACKING_IMAGE_STATUS_DATA::NAME => Some(CAMERA_TRACKING_IMAGE_STATUS_DATA::ID),
36435 CAMERA_TRIGGER_DATA::NAME => Some(CAMERA_TRIGGER_DATA::ID),
36436 CANFD_FRAME_DATA::NAME => Some(CANFD_FRAME_DATA::ID),
36437 CAN_FILTER_MODIFY_DATA::NAME => Some(CAN_FILTER_MODIFY_DATA::ID),
36438 CAN_FRAME_DATA::NAME => Some(CAN_FRAME_DATA::ID),
36439 CELLULAR_CONFIG_DATA::NAME => Some(CELLULAR_CONFIG_DATA::ID),
36440 CELLULAR_STATUS_DATA::NAME => Some(CELLULAR_STATUS_DATA::ID),
36441 CHANGE_OPERATOR_CONTROL_DATA::NAME => Some(CHANGE_OPERATOR_CONTROL_DATA::ID),
36442 CHANGE_OPERATOR_CONTROL_ACK_DATA::NAME => Some(CHANGE_OPERATOR_CONTROL_ACK_DATA::ID),
36443 COLLISION_DATA::NAME => Some(COLLISION_DATA::ID),
36444 COMMAND_ACK_DATA::NAME => Some(COMMAND_ACK_DATA::ID),
36445 COMMAND_CANCEL_DATA::NAME => Some(COMMAND_CANCEL_DATA::ID),
36446 COMMAND_INT_DATA::NAME => Some(COMMAND_INT_DATA::ID),
36447 COMMAND_LONG_DATA::NAME => Some(COMMAND_LONG_DATA::ID),
36448 COMPONENT_INFORMATION_DATA::NAME => Some(COMPONENT_INFORMATION_DATA::ID),
36449 COMPONENT_INFORMATION_BASIC_DATA::NAME => Some(COMPONENT_INFORMATION_BASIC_DATA::ID),
36450 COMPONENT_METADATA_DATA::NAME => Some(COMPONENT_METADATA_DATA::ID),
36451 CONTROL_SYSTEM_STATE_DATA::NAME => Some(CONTROL_SYSTEM_STATE_DATA::ID),
36452 CURRENT_EVENT_SEQUENCE_DATA::NAME => Some(CURRENT_EVENT_SEQUENCE_DATA::ID),
36453 CURRENT_MODE_DATA::NAME => Some(CURRENT_MODE_DATA::ID),
36454 DATA_STREAM_DATA::NAME => Some(DATA_STREAM_DATA::ID),
36455 DATA_TRANSMISSION_HANDSHAKE_DATA::NAME => Some(DATA_TRANSMISSION_HANDSHAKE_DATA::ID),
36456 DEBUG_DATA::NAME => Some(DEBUG_DATA::ID),
36457 DEBUG_FLOAT_ARRAY_DATA::NAME => Some(DEBUG_FLOAT_ARRAY_DATA::ID),
36458 DEBUG_VECT_DATA::NAME => Some(DEBUG_VECT_DATA::ID),
36459 DISTANCE_SENSOR_DATA::NAME => Some(DISTANCE_SENSOR_DATA::ID),
36460 EFI_STATUS_DATA::NAME => Some(EFI_STATUS_DATA::ID),
36461 ENCAPSULATED_DATA_DATA::NAME => Some(ENCAPSULATED_DATA_DATA::ID),
36462 ESC_INFO_DATA::NAME => Some(ESC_INFO_DATA::ID),
36463 ESC_STATUS_DATA::NAME => Some(ESC_STATUS_DATA::ID),
36464 ESTIMATOR_STATUS_DATA::NAME => Some(ESTIMATOR_STATUS_DATA::ID),
36465 EVENT_DATA::NAME => Some(EVENT_DATA::ID),
36466 EXTENDED_SYS_STATE_DATA::NAME => Some(EXTENDED_SYS_STATE_DATA::ID),
36467 FENCE_STATUS_DATA::NAME => Some(FENCE_STATUS_DATA::ID),
36468 FILE_TRANSFER_PROTOCOL_DATA::NAME => Some(FILE_TRANSFER_PROTOCOL_DATA::ID),
36469 FLIGHT_INFORMATION_DATA::NAME => Some(FLIGHT_INFORMATION_DATA::ID),
36470 FOLLOW_TARGET_DATA::NAME => Some(FOLLOW_TARGET_DATA::ID),
36471 FUEL_STATUS_DATA::NAME => Some(FUEL_STATUS_DATA::ID),
36472 GENERATOR_STATUS_DATA::NAME => Some(GENERATOR_STATUS_DATA::ID),
36473 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::NAME => {
36474 Some(GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID)
36475 }
36476 GIMBAL_DEVICE_INFORMATION_DATA::NAME => Some(GIMBAL_DEVICE_INFORMATION_DATA::ID),
36477 GIMBAL_DEVICE_SET_ATTITUDE_DATA::NAME => Some(GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID),
36478 GIMBAL_MANAGER_INFORMATION_DATA::NAME => Some(GIMBAL_MANAGER_INFORMATION_DATA::ID),
36479 GIMBAL_MANAGER_SET_ATTITUDE_DATA::NAME => Some(GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID),
36480 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::NAME => {
36481 Some(GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID)
36482 }
36483 GIMBAL_MANAGER_SET_PITCHYAW_DATA::NAME => Some(GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID),
36484 GIMBAL_MANAGER_STATUS_DATA::NAME => Some(GIMBAL_MANAGER_STATUS_DATA::ID),
36485 GLOBAL_POSITION_INT_DATA::NAME => Some(GLOBAL_POSITION_INT_DATA::ID),
36486 GLOBAL_POSITION_INT_COV_DATA::NAME => Some(GLOBAL_POSITION_INT_COV_DATA::ID),
36487 GLOBAL_VISION_POSITION_ESTIMATE_DATA::NAME => {
36488 Some(GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID)
36489 }
36490 GPS2_RAW_DATA::NAME => Some(GPS2_RAW_DATA::ID),
36491 GPS2_RTK_DATA::NAME => Some(GPS2_RTK_DATA::ID),
36492 GPS_GLOBAL_ORIGIN_DATA::NAME => Some(GPS_GLOBAL_ORIGIN_DATA::ID),
36493 GPS_INJECT_DATA_DATA::NAME => Some(GPS_INJECT_DATA_DATA::ID),
36494 GPS_INPUT_DATA::NAME => Some(GPS_INPUT_DATA::ID),
36495 GPS_RAW_INT_DATA::NAME => Some(GPS_RAW_INT_DATA::ID),
36496 GPS_RTCM_DATA_DATA::NAME => Some(GPS_RTCM_DATA_DATA::ID),
36497 GPS_RTK_DATA::NAME => Some(GPS_RTK_DATA::ID),
36498 GPS_STATUS_DATA::NAME => Some(GPS_STATUS_DATA::ID),
36499 HEARTBEAT_DATA::NAME => Some(HEARTBEAT_DATA::ID),
36500 HIGHRES_IMU_DATA::NAME => Some(HIGHRES_IMU_DATA::ID),
36501 HIGH_LATENCY_DATA::NAME => Some(HIGH_LATENCY_DATA::ID),
36502 HIGH_LATENCY2_DATA::NAME => Some(HIGH_LATENCY2_DATA::ID),
36503 HIL_ACTUATOR_CONTROLS_DATA::NAME => Some(HIL_ACTUATOR_CONTROLS_DATA::ID),
36504 HIL_CONTROLS_DATA::NAME => Some(HIL_CONTROLS_DATA::ID),
36505 HIL_GPS_DATA::NAME => Some(HIL_GPS_DATA::ID),
36506 HIL_OPTICAL_FLOW_DATA::NAME => Some(HIL_OPTICAL_FLOW_DATA::ID),
36507 HIL_RC_INPUTS_RAW_DATA::NAME => Some(HIL_RC_INPUTS_RAW_DATA::ID),
36508 HIL_SENSOR_DATA::NAME => Some(HIL_SENSOR_DATA::ID),
36509 HIL_STATE_DATA::NAME => Some(HIL_STATE_DATA::ID),
36510 HIL_STATE_QUATERNION_DATA::NAME => Some(HIL_STATE_QUATERNION_DATA::ID),
36511 HOME_POSITION_DATA::NAME => Some(HOME_POSITION_DATA::ID),
36512 HYGROMETER_SENSOR_DATA::NAME => Some(HYGROMETER_SENSOR_DATA::ID),
36513 ILLUMINATOR_STATUS_DATA::NAME => Some(ILLUMINATOR_STATUS_DATA::ID),
36514 ISBD_LINK_STATUS_DATA::NAME => Some(ISBD_LINK_STATUS_DATA::ID),
36515 LANDING_TARGET_DATA::NAME => Some(LANDING_TARGET_DATA::ID),
36516 LINK_NODE_STATUS_DATA::NAME => Some(LINK_NODE_STATUS_DATA::ID),
36517 LOCAL_POSITION_NED_DATA::NAME => Some(LOCAL_POSITION_NED_DATA::ID),
36518 LOCAL_POSITION_NED_COV_DATA::NAME => Some(LOCAL_POSITION_NED_COV_DATA::ID),
36519 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::NAME => {
36520 Some(LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID)
36521 }
36522 LOGGING_ACK_DATA::NAME => Some(LOGGING_ACK_DATA::ID),
36523 LOGGING_DATA_DATA::NAME => Some(LOGGING_DATA_DATA::ID),
36524 LOGGING_DATA_ACKED_DATA::NAME => Some(LOGGING_DATA_ACKED_DATA::ID),
36525 LOG_DATA_DATA::NAME => Some(LOG_DATA_DATA::ID),
36526 LOG_ENTRY_DATA::NAME => Some(LOG_ENTRY_DATA::ID),
36527 LOG_ERASE_DATA::NAME => Some(LOG_ERASE_DATA::ID),
36528 LOG_REQUEST_DATA_DATA::NAME => Some(LOG_REQUEST_DATA_DATA::ID),
36529 LOG_REQUEST_END_DATA::NAME => Some(LOG_REQUEST_END_DATA::ID),
36530 LOG_REQUEST_LIST_DATA::NAME => Some(LOG_REQUEST_LIST_DATA::ID),
36531 MAG_CAL_REPORT_DATA::NAME => Some(MAG_CAL_REPORT_DATA::ID),
36532 MANUAL_CONTROL_DATA::NAME => Some(MANUAL_CONTROL_DATA::ID),
36533 MANUAL_SETPOINT_DATA::NAME => Some(MANUAL_SETPOINT_DATA::ID),
36534 MEMORY_VECT_DATA::NAME => Some(MEMORY_VECT_DATA::ID),
36535 MESSAGE_INTERVAL_DATA::NAME => Some(MESSAGE_INTERVAL_DATA::ID),
36536 MISSION_ACK_DATA::NAME => Some(MISSION_ACK_DATA::ID),
36537 MISSION_CLEAR_ALL_DATA::NAME => Some(MISSION_CLEAR_ALL_DATA::ID),
36538 MISSION_COUNT_DATA::NAME => Some(MISSION_COUNT_DATA::ID),
36539 MISSION_CURRENT_DATA::NAME => Some(MISSION_CURRENT_DATA::ID),
36540 MISSION_ITEM_DATA::NAME => Some(MISSION_ITEM_DATA::ID),
36541 MISSION_ITEM_INT_DATA::NAME => Some(MISSION_ITEM_INT_DATA::ID),
36542 MISSION_ITEM_REACHED_DATA::NAME => Some(MISSION_ITEM_REACHED_DATA::ID),
36543 MISSION_REQUEST_DATA::NAME => Some(MISSION_REQUEST_DATA::ID),
36544 MISSION_REQUEST_INT_DATA::NAME => Some(MISSION_REQUEST_INT_DATA::ID),
36545 MISSION_REQUEST_LIST_DATA::NAME => Some(MISSION_REQUEST_LIST_DATA::ID),
36546 MISSION_REQUEST_PARTIAL_LIST_DATA::NAME => Some(MISSION_REQUEST_PARTIAL_LIST_DATA::ID),
36547 MISSION_SET_CURRENT_DATA::NAME => Some(MISSION_SET_CURRENT_DATA::ID),
36548 MISSION_WRITE_PARTIAL_LIST_DATA::NAME => Some(MISSION_WRITE_PARTIAL_LIST_DATA::ID),
36549 MOUNT_ORIENTATION_DATA::NAME => Some(MOUNT_ORIENTATION_DATA::ID),
36550 NAMED_VALUE_FLOAT_DATA::NAME => Some(NAMED_VALUE_FLOAT_DATA::ID),
36551 NAMED_VALUE_INT_DATA::NAME => Some(NAMED_VALUE_INT_DATA::ID),
36552 NAV_CONTROLLER_OUTPUT_DATA::NAME => Some(NAV_CONTROLLER_OUTPUT_DATA::ID),
36553 OBSTACLE_DISTANCE_DATA::NAME => Some(OBSTACLE_DISTANCE_DATA::ID),
36554 ODOMETRY_DATA::NAME => Some(ODOMETRY_DATA::ID),
36555 ONBOARD_COMPUTER_STATUS_DATA::NAME => Some(ONBOARD_COMPUTER_STATUS_DATA::ID),
36556 OPEN_DRONE_ID_ARM_STATUS_DATA::NAME => Some(OPEN_DRONE_ID_ARM_STATUS_DATA::ID),
36557 OPEN_DRONE_ID_AUTHENTICATION_DATA::NAME => Some(OPEN_DRONE_ID_AUTHENTICATION_DATA::ID),
36558 OPEN_DRONE_ID_BASIC_ID_DATA::NAME => Some(OPEN_DRONE_ID_BASIC_ID_DATA::ID),
36559 OPEN_DRONE_ID_LOCATION_DATA::NAME => Some(OPEN_DRONE_ID_LOCATION_DATA::ID),
36560 OPEN_DRONE_ID_MESSAGE_PACK_DATA::NAME => Some(OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID),
36561 OPEN_DRONE_ID_OPERATOR_ID_DATA::NAME => Some(OPEN_DRONE_ID_OPERATOR_ID_DATA::ID),
36562 OPEN_DRONE_ID_SELF_ID_DATA::NAME => Some(OPEN_DRONE_ID_SELF_ID_DATA::ID),
36563 OPEN_DRONE_ID_SYSTEM_DATA::NAME => Some(OPEN_DRONE_ID_SYSTEM_DATA::ID),
36564 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::NAME => Some(OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID),
36565 OPTICAL_FLOW_DATA::NAME => Some(OPTICAL_FLOW_DATA::ID),
36566 OPTICAL_FLOW_RAD_DATA::NAME => Some(OPTICAL_FLOW_RAD_DATA::ID),
36567 ORBIT_EXECUTION_STATUS_DATA::NAME => Some(ORBIT_EXECUTION_STATUS_DATA::ID),
36568 PARAM_EXT_ACK_DATA::NAME => Some(PARAM_EXT_ACK_DATA::ID),
36569 PARAM_EXT_REQUEST_LIST_DATA::NAME => Some(PARAM_EXT_REQUEST_LIST_DATA::ID),
36570 PARAM_EXT_REQUEST_READ_DATA::NAME => Some(PARAM_EXT_REQUEST_READ_DATA::ID),
36571 PARAM_EXT_SET_DATA::NAME => Some(PARAM_EXT_SET_DATA::ID),
36572 PARAM_EXT_VALUE_DATA::NAME => Some(PARAM_EXT_VALUE_DATA::ID),
36573 PARAM_MAP_RC_DATA::NAME => Some(PARAM_MAP_RC_DATA::ID),
36574 PARAM_REQUEST_LIST_DATA::NAME => Some(PARAM_REQUEST_LIST_DATA::ID),
36575 PARAM_REQUEST_READ_DATA::NAME => Some(PARAM_REQUEST_READ_DATA::ID),
36576 PARAM_SET_DATA::NAME => Some(PARAM_SET_DATA::ID),
36577 PARAM_VALUE_DATA::NAME => Some(PARAM_VALUE_DATA::ID),
36578 PING_DATA::NAME => Some(PING_DATA::ID),
36579 PLAY_TUNE_DATA::NAME => Some(PLAY_TUNE_DATA::ID),
36580 PLAY_TUNE_V2_DATA::NAME => Some(PLAY_TUNE_V2_DATA::ID),
36581 POSITION_TARGET_GLOBAL_INT_DATA::NAME => Some(POSITION_TARGET_GLOBAL_INT_DATA::ID),
36582 POSITION_TARGET_LOCAL_NED_DATA::NAME => Some(POSITION_TARGET_LOCAL_NED_DATA::ID),
36583 POWER_STATUS_DATA::NAME => Some(POWER_STATUS_DATA::ID),
36584 PROTOCOL_VERSION_DATA::NAME => Some(PROTOCOL_VERSION_DATA::ID),
36585 RADIO_STATUS_DATA::NAME => Some(RADIO_STATUS_DATA::ID),
36586 RAW_IMU_DATA::NAME => Some(RAW_IMU_DATA::ID),
36587 RAW_PRESSURE_DATA::NAME => Some(RAW_PRESSURE_DATA::ID),
36588 RAW_RPM_DATA::NAME => Some(RAW_RPM_DATA::ID),
36589 RC_CHANNELS_DATA::NAME => Some(RC_CHANNELS_DATA::ID),
36590 RC_CHANNELS_OVERRIDE_DATA::NAME => Some(RC_CHANNELS_OVERRIDE_DATA::ID),
36591 RC_CHANNELS_RAW_DATA::NAME => Some(RC_CHANNELS_RAW_DATA::ID),
36592 RC_CHANNELS_SCALED_DATA::NAME => Some(RC_CHANNELS_SCALED_DATA::ID),
36593 REQUEST_DATA_STREAM_DATA::NAME => Some(REQUEST_DATA_STREAM_DATA::ID),
36594 REQUEST_EVENT_DATA::NAME => Some(REQUEST_EVENT_DATA::ID),
36595 RESOURCE_REQUEST_DATA::NAME => Some(RESOURCE_REQUEST_DATA::ID),
36596 RESPONSE_EVENT_ERROR_DATA::NAME => Some(RESPONSE_EVENT_ERROR_DATA::ID),
36597 SAFETY_ALLOWED_AREA_DATA::NAME => Some(SAFETY_ALLOWED_AREA_DATA::ID),
36598 SAFETY_SET_ALLOWED_AREA_DATA::NAME => Some(SAFETY_SET_ALLOWED_AREA_DATA::ID),
36599 SCALED_IMU_DATA::NAME => Some(SCALED_IMU_DATA::ID),
36600 SCALED_IMU2_DATA::NAME => Some(SCALED_IMU2_DATA::ID),
36601 SCALED_IMU3_DATA::NAME => Some(SCALED_IMU3_DATA::ID),
36602 SCALED_PRESSURE_DATA::NAME => Some(SCALED_PRESSURE_DATA::ID),
36603 SCALED_PRESSURE2_DATA::NAME => Some(SCALED_PRESSURE2_DATA::ID),
36604 SCALED_PRESSURE3_DATA::NAME => Some(SCALED_PRESSURE3_DATA::ID),
36605 SERIAL_CONTROL_DATA::NAME => Some(SERIAL_CONTROL_DATA::ID),
36606 SERVO_OUTPUT_RAW_DATA::NAME => Some(SERVO_OUTPUT_RAW_DATA::ID),
36607 SETUP_SIGNING_DATA::NAME => Some(SETUP_SIGNING_DATA::ID),
36608 SET_ACTUATOR_CONTROL_TARGET_DATA::NAME => Some(SET_ACTUATOR_CONTROL_TARGET_DATA::ID),
36609 SET_ATTITUDE_TARGET_DATA::NAME => Some(SET_ATTITUDE_TARGET_DATA::ID),
36610 SET_GPS_GLOBAL_ORIGIN_DATA::NAME => Some(SET_GPS_GLOBAL_ORIGIN_DATA::ID),
36611 SET_HOME_POSITION_DATA::NAME => Some(SET_HOME_POSITION_DATA::ID),
36612 SET_MODE_DATA::NAME => Some(SET_MODE_DATA::ID),
36613 SET_POSITION_TARGET_GLOBAL_INT_DATA::NAME => {
36614 Some(SET_POSITION_TARGET_GLOBAL_INT_DATA::ID)
36615 }
36616 SET_POSITION_TARGET_LOCAL_NED_DATA::NAME => {
36617 Some(SET_POSITION_TARGET_LOCAL_NED_DATA::ID)
36618 }
36619 SIM_STATE_DATA::NAME => Some(SIM_STATE_DATA::ID),
36620 SMART_BATTERY_INFO_DATA::NAME => Some(SMART_BATTERY_INFO_DATA::ID),
36621 STATUSTEXT_DATA::NAME => Some(STATUSTEXT_DATA::ID),
36622 STORAGE_INFORMATION_DATA::NAME => Some(STORAGE_INFORMATION_DATA::ID),
36623 SUPPORTED_TUNES_DATA::NAME => Some(SUPPORTED_TUNES_DATA::ID),
36624 SYSTEM_TIME_DATA::NAME => Some(SYSTEM_TIME_DATA::ID),
36625 SYS_STATUS_DATA::NAME => Some(SYS_STATUS_DATA::ID),
36626 TERRAIN_CHECK_DATA::NAME => Some(TERRAIN_CHECK_DATA::ID),
36627 TERRAIN_DATA_DATA::NAME => Some(TERRAIN_DATA_DATA::ID),
36628 TERRAIN_REPORT_DATA::NAME => Some(TERRAIN_REPORT_DATA::ID),
36629 TERRAIN_REQUEST_DATA::NAME => Some(TERRAIN_REQUEST_DATA::ID),
36630 TIMESYNC_DATA::NAME => Some(TIMESYNC_DATA::ID),
36631 TIME_ESTIMATE_TO_TARGET_DATA::NAME => Some(TIME_ESTIMATE_TO_TARGET_DATA::ID),
36632 TRAJECTORY_REPRESENTATION_BEZIER_DATA::NAME => {
36633 Some(TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID)
36634 }
36635 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::NAME => {
36636 Some(TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID)
36637 }
36638 TUNNEL_DATA::NAME => Some(TUNNEL_DATA::ID),
36639 UAVCAN_NODE_INFO_DATA::NAME => Some(UAVCAN_NODE_INFO_DATA::ID),
36640 UAVCAN_NODE_STATUS_DATA::NAME => Some(UAVCAN_NODE_STATUS_DATA::ID),
36641 UTM_GLOBAL_POSITION_DATA::NAME => Some(UTM_GLOBAL_POSITION_DATA::ID),
36642 V2_EXTENSION_DATA::NAME => Some(V2_EXTENSION_DATA::ID),
36643 VFR_HUD_DATA::NAME => Some(VFR_HUD_DATA::ID),
36644 VIBRATION_DATA::NAME => Some(VIBRATION_DATA::ID),
36645 VICON_POSITION_ESTIMATE_DATA::NAME => Some(VICON_POSITION_ESTIMATE_DATA::ID),
36646 VIDEO_STREAM_INFORMATION_DATA::NAME => Some(VIDEO_STREAM_INFORMATION_DATA::ID),
36647 VIDEO_STREAM_STATUS_DATA::NAME => Some(VIDEO_STREAM_STATUS_DATA::ID),
36648 VISION_POSITION_ESTIMATE_DATA::NAME => Some(VISION_POSITION_ESTIMATE_DATA::ID),
36649 VISION_SPEED_ESTIMATE_DATA::NAME => Some(VISION_SPEED_ESTIMATE_DATA::ID),
36650 WHEEL_DISTANCE_DATA::NAME => Some(WHEEL_DISTANCE_DATA::ID),
36651 WIFI_CONFIG_AP_DATA::NAME => Some(WIFI_CONFIG_AP_DATA::ID),
36652 WINCH_STATUS_DATA::NAME => Some(WINCH_STATUS_DATA::ID),
36653 WIND_COV_DATA::NAME => Some(WIND_COV_DATA::ID),
36654 _ => None,
36655 }
36656 }
36657 fn default_message_from_id(id: u32) -> Option<Self> {
36658 match id {
36659 ACTUATOR_CONTROL_TARGET_DATA::ID => Some(Self::ACTUATOR_CONTROL_TARGET(
36660 ACTUATOR_CONTROL_TARGET_DATA::default(),
36661 )),
36662 ACTUATOR_OUTPUT_STATUS_DATA::ID => Some(Self::ACTUATOR_OUTPUT_STATUS(
36663 ACTUATOR_OUTPUT_STATUS_DATA::default(),
36664 )),
36665 ADSB_VEHICLE_DATA::ID => Some(Self::ADSB_VEHICLE(ADSB_VEHICLE_DATA::default())),
36666 AIS_VESSEL_DATA::ID => Some(Self::AIS_VESSEL(AIS_VESSEL_DATA::default())),
36667 ALTITUDE_DATA::ID => Some(Self::ALTITUDE(ALTITUDE_DATA::default())),
36668 ATTITUDE_DATA::ID => Some(Self::ATTITUDE(ATTITUDE_DATA::default())),
36669 ATTITUDE_QUATERNION_DATA::ID => Some(Self::ATTITUDE_QUATERNION(
36670 ATTITUDE_QUATERNION_DATA::default(),
36671 )),
36672 ATTITUDE_QUATERNION_COV_DATA::ID => Some(Self::ATTITUDE_QUATERNION_COV(
36673 ATTITUDE_QUATERNION_COV_DATA::default(),
36674 )),
36675 ATTITUDE_TARGET_DATA::ID => {
36676 Some(Self::ATTITUDE_TARGET(ATTITUDE_TARGET_DATA::default()))
36677 }
36678 ATT_POS_MOCAP_DATA::ID => Some(Self::ATT_POS_MOCAP(ATT_POS_MOCAP_DATA::default())),
36679 AUTH_KEY_DATA::ID => Some(Self::AUTH_KEY(AUTH_KEY_DATA::default())),
36680 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID => {
36681 Some(Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(
36682 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::default(),
36683 ))
36684 }
36685 AUTOPILOT_VERSION_DATA::ID => {
36686 Some(Self::AUTOPILOT_VERSION(AUTOPILOT_VERSION_DATA::default()))
36687 }
36688 AVAILABLE_MODES_DATA::ID => {
36689 Some(Self::AVAILABLE_MODES(AVAILABLE_MODES_DATA::default()))
36690 }
36691 AVAILABLE_MODES_MONITOR_DATA::ID => Some(Self::AVAILABLE_MODES_MONITOR(
36692 AVAILABLE_MODES_MONITOR_DATA::default(),
36693 )),
36694 BATTERY_INFO_DATA::ID => Some(Self::BATTERY_INFO(BATTERY_INFO_DATA::default())),
36695 BATTERY_STATUS_DATA::ID => Some(Self::BATTERY_STATUS(BATTERY_STATUS_DATA::default())),
36696 BUTTON_CHANGE_DATA::ID => Some(Self::BUTTON_CHANGE(BUTTON_CHANGE_DATA::default())),
36697 CAMERA_CAPTURE_STATUS_DATA::ID => Some(Self::CAMERA_CAPTURE_STATUS(
36698 CAMERA_CAPTURE_STATUS_DATA::default(),
36699 )),
36700 CAMERA_FOV_STATUS_DATA::ID => {
36701 Some(Self::CAMERA_FOV_STATUS(CAMERA_FOV_STATUS_DATA::default()))
36702 }
36703 CAMERA_IMAGE_CAPTURED_DATA::ID => Some(Self::CAMERA_IMAGE_CAPTURED(
36704 CAMERA_IMAGE_CAPTURED_DATA::default(),
36705 )),
36706 CAMERA_INFORMATION_DATA::ID => {
36707 Some(Self::CAMERA_INFORMATION(CAMERA_INFORMATION_DATA::default()))
36708 }
36709 CAMERA_SETTINGS_DATA::ID => {
36710 Some(Self::CAMERA_SETTINGS(CAMERA_SETTINGS_DATA::default()))
36711 }
36712 CAMERA_THERMAL_RANGE_DATA::ID => Some(Self::CAMERA_THERMAL_RANGE(
36713 CAMERA_THERMAL_RANGE_DATA::default(),
36714 )),
36715 CAMERA_TRACKING_GEO_STATUS_DATA::ID => Some(Self::CAMERA_TRACKING_GEO_STATUS(
36716 CAMERA_TRACKING_GEO_STATUS_DATA::default(),
36717 )),
36718 CAMERA_TRACKING_IMAGE_STATUS_DATA::ID => Some(Self::CAMERA_TRACKING_IMAGE_STATUS(
36719 CAMERA_TRACKING_IMAGE_STATUS_DATA::default(),
36720 )),
36721 CAMERA_TRIGGER_DATA::ID => Some(Self::CAMERA_TRIGGER(CAMERA_TRIGGER_DATA::default())),
36722 CANFD_FRAME_DATA::ID => Some(Self::CANFD_FRAME(CANFD_FRAME_DATA::default())),
36723 CAN_FILTER_MODIFY_DATA::ID => {
36724 Some(Self::CAN_FILTER_MODIFY(CAN_FILTER_MODIFY_DATA::default()))
36725 }
36726 CAN_FRAME_DATA::ID => Some(Self::CAN_FRAME(CAN_FRAME_DATA::default())),
36727 CELLULAR_CONFIG_DATA::ID => {
36728 Some(Self::CELLULAR_CONFIG(CELLULAR_CONFIG_DATA::default()))
36729 }
36730 CELLULAR_STATUS_DATA::ID => {
36731 Some(Self::CELLULAR_STATUS(CELLULAR_STATUS_DATA::default()))
36732 }
36733 CHANGE_OPERATOR_CONTROL_DATA::ID => Some(Self::CHANGE_OPERATOR_CONTROL(
36734 CHANGE_OPERATOR_CONTROL_DATA::default(),
36735 )),
36736 CHANGE_OPERATOR_CONTROL_ACK_DATA::ID => Some(Self::CHANGE_OPERATOR_CONTROL_ACK(
36737 CHANGE_OPERATOR_CONTROL_ACK_DATA::default(),
36738 )),
36739 COLLISION_DATA::ID => Some(Self::COLLISION(COLLISION_DATA::default())),
36740 COMMAND_ACK_DATA::ID => Some(Self::COMMAND_ACK(COMMAND_ACK_DATA::default())),
36741 COMMAND_CANCEL_DATA::ID => Some(Self::COMMAND_CANCEL(COMMAND_CANCEL_DATA::default())),
36742 COMMAND_INT_DATA::ID => Some(Self::COMMAND_INT(COMMAND_INT_DATA::default())),
36743 COMMAND_LONG_DATA::ID => Some(Self::COMMAND_LONG(COMMAND_LONG_DATA::default())),
36744 COMPONENT_INFORMATION_DATA::ID => Some(Self::COMPONENT_INFORMATION(
36745 COMPONENT_INFORMATION_DATA::default(),
36746 )),
36747 COMPONENT_INFORMATION_BASIC_DATA::ID => Some(Self::COMPONENT_INFORMATION_BASIC(
36748 COMPONENT_INFORMATION_BASIC_DATA::default(),
36749 )),
36750 COMPONENT_METADATA_DATA::ID => {
36751 Some(Self::COMPONENT_METADATA(COMPONENT_METADATA_DATA::default()))
36752 }
36753 CONTROL_SYSTEM_STATE_DATA::ID => Some(Self::CONTROL_SYSTEM_STATE(
36754 CONTROL_SYSTEM_STATE_DATA::default(),
36755 )),
36756 CURRENT_EVENT_SEQUENCE_DATA::ID => Some(Self::CURRENT_EVENT_SEQUENCE(
36757 CURRENT_EVENT_SEQUENCE_DATA::default(),
36758 )),
36759 CURRENT_MODE_DATA::ID => Some(Self::CURRENT_MODE(CURRENT_MODE_DATA::default())),
36760 DATA_STREAM_DATA::ID => Some(Self::DATA_STREAM(DATA_STREAM_DATA::default())),
36761 DATA_TRANSMISSION_HANDSHAKE_DATA::ID => Some(Self::DATA_TRANSMISSION_HANDSHAKE(
36762 DATA_TRANSMISSION_HANDSHAKE_DATA::default(),
36763 )),
36764 DEBUG_DATA::ID => Some(Self::DEBUG(DEBUG_DATA::default())),
36765 DEBUG_FLOAT_ARRAY_DATA::ID => {
36766 Some(Self::DEBUG_FLOAT_ARRAY(DEBUG_FLOAT_ARRAY_DATA::default()))
36767 }
36768 DEBUG_VECT_DATA::ID => Some(Self::DEBUG_VECT(DEBUG_VECT_DATA::default())),
36769 DISTANCE_SENSOR_DATA::ID => {
36770 Some(Self::DISTANCE_SENSOR(DISTANCE_SENSOR_DATA::default()))
36771 }
36772 EFI_STATUS_DATA::ID => Some(Self::EFI_STATUS(EFI_STATUS_DATA::default())),
36773 ENCAPSULATED_DATA_DATA::ID => {
36774 Some(Self::ENCAPSULATED_DATA(ENCAPSULATED_DATA_DATA::default()))
36775 }
36776 ESC_INFO_DATA::ID => Some(Self::ESC_INFO(ESC_INFO_DATA::default())),
36777 ESC_STATUS_DATA::ID => Some(Self::ESC_STATUS(ESC_STATUS_DATA::default())),
36778 ESTIMATOR_STATUS_DATA::ID => {
36779 Some(Self::ESTIMATOR_STATUS(ESTIMATOR_STATUS_DATA::default()))
36780 }
36781 EVENT_DATA::ID => Some(Self::EVENT(EVENT_DATA::default())),
36782 EXTENDED_SYS_STATE_DATA::ID => {
36783 Some(Self::EXTENDED_SYS_STATE(EXTENDED_SYS_STATE_DATA::default()))
36784 }
36785 FENCE_STATUS_DATA::ID => Some(Self::FENCE_STATUS(FENCE_STATUS_DATA::default())),
36786 FILE_TRANSFER_PROTOCOL_DATA::ID => Some(Self::FILE_TRANSFER_PROTOCOL(
36787 FILE_TRANSFER_PROTOCOL_DATA::default(),
36788 )),
36789 FLIGHT_INFORMATION_DATA::ID => {
36790 Some(Self::FLIGHT_INFORMATION(FLIGHT_INFORMATION_DATA::default()))
36791 }
36792 FOLLOW_TARGET_DATA::ID => Some(Self::FOLLOW_TARGET(FOLLOW_TARGET_DATA::default())),
36793 FUEL_STATUS_DATA::ID => Some(Self::FUEL_STATUS(FUEL_STATUS_DATA::default())),
36794 GENERATOR_STATUS_DATA::ID => {
36795 Some(Self::GENERATOR_STATUS(GENERATOR_STATUS_DATA::default()))
36796 }
36797 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID => Some(Self::GIMBAL_DEVICE_ATTITUDE_STATUS(
36798 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::default(),
36799 )),
36800 GIMBAL_DEVICE_INFORMATION_DATA::ID => Some(Self::GIMBAL_DEVICE_INFORMATION(
36801 GIMBAL_DEVICE_INFORMATION_DATA::default(),
36802 )),
36803 GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID => Some(Self::GIMBAL_DEVICE_SET_ATTITUDE(
36804 GIMBAL_DEVICE_SET_ATTITUDE_DATA::default(),
36805 )),
36806 GIMBAL_MANAGER_INFORMATION_DATA::ID => Some(Self::GIMBAL_MANAGER_INFORMATION(
36807 GIMBAL_MANAGER_INFORMATION_DATA::default(),
36808 )),
36809 GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID => Some(Self::GIMBAL_MANAGER_SET_ATTITUDE(
36810 GIMBAL_MANAGER_SET_ATTITUDE_DATA::default(),
36811 )),
36812 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID => {
36813 Some(Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(
36814 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::default(),
36815 ))
36816 }
36817 GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID => Some(Self::GIMBAL_MANAGER_SET_PITCHYAW(
36818 GIMBAL_MANAGER_SET_PITCHYAW_DATA::default(),
36819 )),
36820 GIMBAL_MANAGER_STATUS_DATA::ID => Some(Self::GIMBAL_MANAGER_STATUS(
36821 GIMBAL_MANAGER_STATUS_DATA::default(),
36822 )),
36823 GLOBAL_POSITION_INT_DATA::ID => Some(Self::GLOBAL_POSITION_INT(
36824 GLOBAL_POSITION_INT_DATA::default(),
36825 )),
36826 GLOBAL_POSITION_INT_COV_DATA::ID => Some(Self::GLOBAL_POSITION_INT_COV(
36827 GLOBAL_POSITION_INT_COV_DATA::default(),
36828 )),
36829 GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID => {
36830 Some(Self::GLOBAL_VISION_POSITION_ESTIMATE(
36831 GLOBAL_VISION_POSITION_ESTIMATE_DATA::default(),
36832 ))
36833 }
36834 GPS2_RAW_DATA::ID => Some(Self::GPS2_RAW(GPS2_RAW_DATA::default())),
36835 GPS2_RTK_DATA::ID => Some(Self::GPS2_RTK(GPS2_RTK_DATA::default())),
36836 GPS_GLOBAL_ORIGIN_DATA::ID => {
36837 Some(Self::GPS_GLOBAL_ORIGIN(GPS_GLOBAL_ORIGIN_DATA::default()))
36838 }
36839 GPS_INJECT_DATA_DATA::ID => {
36840 Some(Self::GPS_INJECT_DATA(GPS_INJECT_DATA_DATA::default()))
36841 }
36842 GPS_INPUT_DATA::ID => Some(Self::GPS_INPUT(GPS_INPUT_DATA::default())),
36843 GPS_RAW_INT_DATA::ID => Some(Self::GPS_RAW_INT(GPS_RAW_INT_DATA::default())),
36844 GPS_RTCM_DATA_DATA::ID => Some(Self::GPS_RTCM_DATA(GPS_RTCM_DATA_DATA::default())),
36845 GPS_RTK_DATA::ID => Some(Self::GPS_RTK(GPS_RTK_DATA::default())),
36846 GPS_STATUS_DATA::ID => Some(Self::GPS_STATUS(GPS_STATUS_DATA::default())),
36847 HEARTBEAT_DATA::ID => Some(Self::HEARTBEAT(HEARTBEAT_DATA::default())),
36848 HIGHRES_IMU_DATA::ID => Some(Self::HIGHRES_IMU(HIGHRES_IMU_DATA::default())),
36849 HIGH_LATENCY_DATA::ID => Some(Self::HIGH_LATENCY(HIGH_LATENCY_DATA::default())),
36850 HIGH_LATENCY2_DATA::ID => Some(Self::HIGH_LATENCY2(HIGH_LATENCY2_DATA::default())),
36851 HIL_ACTUATOR_CONTROLS_DATA::ID => Some(Self::HIL_ACTUATOR_CONTROLS(
36852 HIL_ACTUATOR_CONTROLS_DATA::default(),
36853 )),
36854 HIL_CONTROLS_DATA::ID => Some(Self::HIL_CONTROLS(HIL_CONTROLS_DATA::default())),
36855 HIL_GPS_DATA::ID => Some(Self::HIL_GPS(HIL_GPS_DATA::default())),
36856 HIL_OPTICAL_FLOW_DATA::ID => {
36857 Some(Self::HIL_OPTICAL_FLOW(HIL_OPTICAL_FLOW_DATA::default()))
36858 }
36859 HIL_RC_INPUTS_RAW_DATA::ID => {
36860 Some(Self::HIL_RC_INPUTS_RAW(HIL_RC_INPUTS_RAW_DATA::default()))
36861 }
36862 HIL_SENSOR_DATA::ID => Some(Self::HIL_SENSOR(HIL_SENSOR_DATA::default())),
36863 HIL_STATE_DATA::ID => Some(Self::HIL_STATE(HIL_STATE_DATA::default())),
36864 HIL_STATE_QUATERNION_DATA::ID => Some(Self::HIL_STATE_QUATERNION(
36865 HIL_STATE_QUATERNION_DATA::default(),
36866 )),
36867 HOME_POSITION_DATA::ID => Some(Self::HOME_POSITION(HOME_POSITION_DATA::default())),
36868 HYGROMETER_SENSOR_DATA::ID => {
36869 Some(Self::HYGROMETER_SENSOR(HYGROMETER_SENSOR_DATA::default()))
36870 }
36871 ILLUMINATOR_STATUS_DATA::ID => {
36872 Some(Self::ILLUMINATOR_STATUS(ILLUMINATOR_STATUS_DATA::default()))
36873 }
36874 ISBD_LINK_STATUS_DATA::ID => {
36875 Some(Self::ISBD_LINK_STATUS(ISBD_LINK_STATUS_DATA::default()))
36876 }
36877 LANDING_TARGET_DATA::ID => Some(Self::LANDING_TARGET(LANDING_TARGET_DATA::default())),
36878 LINK_NODE_STATUS_DATA::ID => {
36879 Some(Self::LINK_NODE_STATUS(LINK_NODE_STATUS_DATA::default()))
36880 }
36881 LOCAL_POSITION_NED_DATA::ID => {
36882 Some(Self::LOCAL_POSITION_NED(LOCAL_POSITION_NED_DATA::default()))
36883 }
36884 LOCAL_POSITION_NED_COV_DATA::ID => Some(Self::LOCAL_POSITION_NED_COV(
36885 LOCAL_POSITION_NED_COV_DATA::default(),
36886 )),
36887 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID => {
36888 Some(Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(
36889 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::default(),
36890 ))
36891 }
36892 LOGGING_ACK_DATA::ID => Some(Self::LOGGING_ACK(LOGGING_ACK_DATA::default())),
36893 LOGGING_DATA_DATA::ID => Some(Self::LOGGING_DATA(LOGGING_DATA_DATA::default())),
36894 LOGGING_DATA_ACKED_DATA::ID => {
36895 Some(Self::LOGGING_DATA_ACKED(LOGGING_DATA_ACKED_DATA::default()))
36896 }
36897 LOG_DATA_DATA::ID => Some(Self::LOG_DATA(LOG_DATA_DATA::default())),
36898 LOG_ENTRY_DATA::ID => Some(Self::LOG_ENTRY(LOG_ENTRY_DATA::default())),
36899 LOG_ERASE_DATA::ID => Some(Self::LOG_ERASE(LOG_ERASE_DATA::default())),
36900 LOG_REQUEST_DATA_DATA::ID => {
36901 Some(Self::LOG_REQUEST_DATA(LOG_REQUEST_DATA_DATA::default()))
36902 }
36903 LOG_REQUEST_END_DATA::ID => {
36904 Some(Self::LOG_REQUEST_END(LOG_REQUEST_END_DATA::default()))
36905 }
36906 LOG_REQUEST_LIST_DATA::ID => {
36907 Some(Self::LOG_REQUEST_LIST(LOG_REQUEST_LIST_DATA::default()))
36908 }
36909 MAG_CAL_REPORT_DATA::ID => Some(Self::MAG_CAL_REPORT(MAG_CAL_REPORT_DATA::default())),
36910 MANUAL_CONTROL_DATA::ID => Some(Self::MANUAL_CONTROL(MANUAL_CONTROL_DATA::default())),
36911 MANUAL_SETPOINT_DATA::ID => {
36912 Some(Self::MANUAL_SETPOINT(MANUAL_SETPOINT_DATA::default()))
36913 }
36914 MEMORY_VECT_DATA::ID => Some(Self::MEMORY_VECT(MEMORY_VECT_DATA::default())),
36915 MESSAGE_INTERVAL_DATA::ID => {
36916 Some(Self::MESSAGE_INTERVAL(MESSAGE_INTERVAL_DATA::default()))
36917 }
36918 MISSION_ACK_DATA::ID => Some(Self::MISSION_ACK(MISSION_ACK_DATA::default())),
36919 MISSION_CLEAR_ALL_DATA::ID => {
36920 Some(Self::MISSION_CLEAR_ALL(MISSION_CLEAR_ALL_DATA::default()))
36921 }
36922 MISSION_COUNT_DATA::ID => Some(Self::MISSION_COUNT(MISSION_COUNT_DATA::default())),
36923 MISSION_CURRENT_DATA::ID => {
36924 Some(Self::MISSION_CURRENT(MISSION_CURRENT_DATA::default()))
36925 }
36926 MISSION_ITEM_DATA::ID => Some(Self::MISSION_ITEM(MISSION_ITEM_DATA::default())),
36927 MISSION_ITEM_INT_DATA::ID => {
36928 Some(Self::MISSION_ITEM_INT(MISSION_ITEM_INT_DATA::default()))
36929 }
36930 MISSION_ITEM_REACHED_DATA::ID => Some(Self::MISSION_ITEM_REACHED(
36931 MISSION_ITEM_REACHED_DATA::default(),
36932 )),
36933 MISSION_REQUEST_DATA::ID => {
36934 Some(Self::MISSION_REQUEST(MISSION_REQUEST_DATA::default()))
36935 }
36936 MISSION_REQUEST_INT_DATA::ID => Some(Self::MISSION_REQUEST_INT(
36937 MISSION_REQUEST_INT_DATA::default(),
36938 )),
36939 MISSION_REQUEST_LIST_DATA::ID => Some(Self::MISSION_REQUEST_LIST(
36940 MISSION_REQUEST_LIST_DATA::default(),
36941 )),
36942 MISSION_REQUEST_PARTIAL_LIST_DATA::ID => Some(Self::MISSION_REQUEST_PARTIAL_LIST(
36943 MISSION_REQUEST_PARTIAL_LIST_DATA::default(),
36944 )),
36945 MISSION_SET_CURRENT_DATA::ID => Some(Self::MISSION_SET_CURRENT(
36946 MISSION_SET_CURRENT_DATA::default(),
36947 )),
36948 MISSION_WRITE_PARTIAL_LIST_DATA::ID => Some(Self::MISSION_WRITE_PARTIAL_LIST(
36949 MISSION_WRITE_PARTIAL_LIST_DATA::default(),
36950 )),
36951 MOUNT_ORIENTATION_DATA::ID => {
36952 Some(Self::MOUNT_ORIENTATION(MOUNT_ORIENTATION_DATA::default()))
36953 }
36954 NAMED_VALUE_FLOAT_DATA::ID => {
36955 Some(Self::NAMED_VALUE_FLOAT(NAMED_VALUE_FLOAT_DATA::default()))
36956 }
36957 NAMED_VALUE_INT_DATA::ID => {
36958 Some(Self::NAMED_VALUE_INT(NAMED_VALUE_INT_DATA::default()))
36959 }
36960 NAV_CONTROLLER_OUTPUT_DATA::ID => Some(Self::NAV_CONTROLLER_OUTPUT(
36961 NAV_CONTROLLER_OUTPUT_DATA::default(),
36962 )),
36963 OBSTACLE_DISTANCE_DATA::ID => {
36964 Some(Self::OBSTACLE_DISTANCE(OBSTACLE_DISTANCE_DATA::default()))
36965 }
36966 ODOMETRY_DATA::ID => Some(Self::ODOMETRY(ODOMETRY_DATA::default())),
36967 ONBOARD_COMPUTER_STATUS_DATA::ID => Some(Self::ONBOARD_COMPUTER_STATUS(
36968 ONBOARD_COMPUTER_STATUS_DATA::default(),
36969 )),
36970 OPEN_DRONE_ID_ARM_STATUS_DATA::ID => Some(Self::OPEN_DRONE_ID_ARM_STATUS(
36971 OPEN_DRONE_ID_ARM_STATUS_DATA::default(),
36972 )),
36973 OPEN_DRONE_ID_AUTHENTICATION_DATA::ID => Some(Self::OPEN_DRONE_ID_AUTHENTICATION(
36974 OPEN_DRONE_ID_AUTHENTICATION_DATA::default(),
36975 )),
36976 OPEN_DRONE_ID_BASIC_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_BASIC_ID(
36977 OPEN_DRONE_ID_BASIC_ID_DATA::default(),
36978 )),
36979 OPEN_DRONE_ID_LOCATION_DATA::ID => Some(Self::OPEN_DRONE_ID_LOCATION(
36980 OPEN_DRONE_ID_LOCATION_DATA::default(),
36981 )),
36982 OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID => Some(Self::OPEN_DRONE_ID_MESSAGE_PACK(
36983 OPEN_DRONE_ID_MESSAGE_PACK_DATA::default(),
36984 )),
36985 OPEN_DRONE_ID_OPERATOR_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_OPERATOR_ID(
36986 OPEN_DRONE_ID_OPERATOR_ID_DATA::default(),
36987 )),
36988 OPEN_DRONE_ID_SELF_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_SELF_ID(
36989 OPEN_DRONE_ID_SELF_ID_DATA::default(),
36990 )),
36991 OPEN_DRONE_ID_SYSTEM_DATA::ID => Some(Self::OPEN_DRONE_ID_SYSTEM(
36992 OPEN_DRONE_ID_SYSTEM_DATA::default(),
36993 )),
36994 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID => Some(Self::OPEN_DRONE_ID_SYSTEM_UPDATE(
36995 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::default(),
36996 )),
36997 OPTICAL_FLOW_DATA::ID => Some(Self::OPTICAL_FLOW(OPTICAL_FLOW_DATA::default())),
36998 OPTICAL_FLOW_RAD_DATA::ID => {
36999 Some(Self::OPTICAL_FLOW_RAD(OPTICAL_FLOW_RAD_DATA::default()))
37000 }
37001 ORBIT_EXECUTION_STATUS_DATA::ID => Some(Self::ORBIT_EXECUTION_STATUS(
37002 ORBIT_EXECUTION_STATUS_DATA::default(),
37003 )),
37004 PARAM_EXT_ACK_DATA::ID => Some(Self::PARAM_EXT_ACK(PARAM_EXT_ACK_DATA::default())),
37005 PARAM_EXT_REQUEST_LIST_DATA::ID => Some(Self::PARAM_EXT_REQUEST_LIST(
37006 PARAM_EXT_REQUEST_LIST_DATA::default(),
37007 )),
37008 PARAM_EXT_REQUEST_READ_DATA::ID => Some(Self::PARAM_EXT_REQUEST_READ(
37009 PARAM_EXT_REQUEST_READ_DATA::default(),
37010 )),
37011 PARAM_EXT_SET_DATA::ID => Some(Self::PARAM_EXT_SET(PARAM_EXT_SET_DATA::default())),
37012 PARAM_EXT_VALUE_DATA::ID => {
37013 Some(Self::PARAM_EXT_VALUE(PARAM_EXT_VALUE_DATA::default()))
37014 }
37015 PARAM_MAP_RC_DATA::ID => Some(Self::PARAM_MAP_RC(PARAM_MAP_RC_DATA::default())),
37016 PARAM_REQUEST_LIST_DATA::ID => {
37017 Some(Self::PARAM_REQUEST_LIST(PARAM_REQUEST_LIST_DATA::default()))
37018 }
37019 PARAM_REQUEST_READ_DATA::ID => {
37020 Some(Self::PARAM_REQUEST_READ(PARAM_REQUEST_READ_DATA::default()))
37021 }
37022 PARAM_SET_DATA::ID => Some(Self::PARAM_SET(PARAM_SET_DATA::default())),
37023 PARAM_VALUE_DATA::ID => Some(Self::PARAM_VALUE(PARAM_VALUE_DATA::default())),
37024 PING_DATA::ID => Some(Self::PING(PING_DATA::default())),
37025 PLAY_TUNE_DATA::ID => Some(Self::PLAY_TUNE(PLAY_TUNE_DATA::default())),
37026 PLAY_TUNE_V2_DATA::ID => Some(Self::PLAY_TUNE_V2(PLAY_TUNE_V2_DATA::default())),
37027 POSITION_TARGET_GLOBAL_INT_DATA::ID => Some(Self::POSITION_TARGET_GLOBAL_INT(
37028 POSITION_TARGET_GLOBAL_INT_DATA::default(),
37029 )),
37030 POSITION_TARGET_LOCAL_NED_DATA::ID => Some(Self::POSITION_TARGET_LOCAL_NED(
37031 POSITION_TARGET_LOCAL_NED_DATA::default(),
37032 )),
37033 POWER_STATUS_DATA::ID => Some(Self::POWER_STATUS(POWER_STATUS_DATA::default())),
37034 PROTOCOL_VERSION_DATA::ID => {
37035 Some(Self::PROTOCOL_VERSION(PROTOCOL_VERSION_DATA::default()))
37036 }
37037 RADIO_STATUS_DATA::ID => Some(Self::RADIO_STATUS(RADIO_STATUS_DATA::default())),
37038 RAW_IMU_DATA::ID => Some(Self::RAW_IMU(RAW_IMU_DATA::default())),
37039 RAW_PRESSURE_DATA::ID => Some(Self::RAW_PRESSURE(RAW_PRESSURE_DATA::default())),
37040 RAW_RPM_DATA::ID => Some(Self::RAW_RPM(RAW_RPM_DATA::default())),
37041 RC_CHANNELS_DATA::ID => Some(Self::RC_CHANNELS(RC_CHANNELS_DATA::default())),
37042 RC_CHANNELS_OVERRIDE_DATA::ID => Some(Self::RC_CHANNELS_OVERRIDE(
37043 RC_CHANNELS_OVERRIDE_DATA::default(),
37044 )),
37045 RC_CHANNELS_RAW_DATA::ID => {
37046 Some(Self::RC_CHANNELS_RAW(RC_CHANNELS_RAW_DATA::default()))
37047 }
37048 RC_CHANNELS_SCALED_DATA::ID => {
37049 Some(Self::RC_CHANNELS_SCALED(RC_CHANNELS_SCALED_DATA::default()))
37050 }
37051 REQUEST_DATA_STREAM_DATA::ID => Some(Self::REQUEST_DATA_STREAM(
37052 REQUEST_DATA_STREAM_DATA::default(),
37053 )),
37054 REQUEST_EVENT_DATA::ID => Some(Self::REQUEST_EVENT(REQUEST_EVENT_DATA::default())),
37055 RESOURCE_REQUEST_DATA::ID => {
37056 Some(Self::RESOURCE_REQUEST(RESOURCE_REQUEST_DATA::default()))
37057 }
37058 RESPONSE_EVENT_ERROR_DATA::ID => Some(Self::RESPONSE_EVENT_ERROR(
37059 RESPONSE_EVENT_ERROR_DATA::default(),
37060 )),
37061 SAFETY_ALLOWED_AREA_DATA::ID => Some(Self::SAFETY_ALLOWED_AREA(
37062 SAFETY_ALLOWED_AREA_DATA::default(),
37063 )),
37064 SAFETY_SET_ALLOWED_AREA_DATA::ID => Some(Self::SAFETY_SET_ALLOWED_AREA(
37065 SAFETY_SET_ALLOWED_AREA_DATA::default(),
37066 )),
37067 SCALED_IMU_DATA::ID => Some(Self::SCALED_IMU(SCALED_IMU_DATA::default())),
37068 SCALED_IMU2_DATA::ID => Some(Self::SCALED_IMU2(SCALED_IMU2_DATA::default())),
37069 SCALED_IMU3_DATA::ID => Some(Self::SCALED_IMU3(SCALED_IMU3_DATA::default())),
37070 SCALED_PRESSURE_DATA::ID => {
37071 Some(Self::SCALED_PRESSURE(SCALED_PRESSURE_DATA::default()))
37072 }
37073 SCALED_PRESSURE2_DATA::ID => {
37074 Some(Self::SCALED_PRESSURE2(SCALED_PRESSURE2_DATA::default()))
37075 }
37076 SCALED_PRESSURE3_DATA::ID => {
37077 Some(Self::SCALED_PRESSURE3(SCALED_PRESSURE3_DATA::default()))
37078 }
37079 SERIAL_CONTROL_DATA::ID => Some(Self::SERIAL_CONTROL(SERIAL_CONTROL_DATA::default())),
37080 SERVO_OUTPUT_RAW_DATA::ID => {
37081 Some(Self::SERVO_OUTPUT_RAW(SERVO_OUTPUT_RAW_DATA::default()))
37082 }
37083 SETUP_SIGNING_DATA::ID => Some(Self::SETUP_SIGNING(SETUP_SIGNING_DATA::default())),
37084 SET_ACTUATOR_CONTROL_TARGET_DATA::ID => Some(Self::SET_ACTUATOR_CONTROL_TARGET(
37085 SET_ACTUATOR_CONTROL_TARGET_DATA::default(),
37086 )),
37087 SET_ATTITUDE_TARGET_DATA::ID => Some(Self::SET_ATTITUDE_TARGET(
37088 SET_ATTITUDE_TARGET_DATA::default(),
37089 )),
37090 SET_GPS_GLOBAL_ORIGIN_DATA::ID => Some(Self::SET_GPS_GLOBAL_ORIGIN(
37091 SET_GPS_GLOBAL_ORIGIN_DATA::default(),
37092 )),
37093 SET_HOME_POSITION_DATA::ID => {
37094 Some(Self::SET_HOME_POSITION(SET_HOME_POSITION_DATA::default()))
37095 }
37096 SET_MODE_DATA::ID => Some(Self::SET_MODE(SET_MODE_DATA::default())),
37097 SET_POSITION_TARGET_GLOBAL_INT_DATA::ID => Some(Self::SET_POSITION_TARGET_GLOBAL_INT(
37098 SET_POSITION_TARGET_GLOBAL_INT_DATA::default(),
37099 )),
37100 SET_POSITION_TARGET_LOCAL_NED_DATA::ID => Some(Self::SET_POSITION_TARGET_LOCAL_NED(
37101 SET_POSITION_TARGET_LOCAL_NED_DATA::default(),
37102 )),
37103 SIM_STATE_DATA::ID => Some(Self::SIM_STATE(SIM_STATE_DATA::default())),
37104 SMART_BATTERY_INFO_DATA::ID => {
37105 Some(Self::SMART_BATTERY_INFO(SMART_BATTERY_INFO_DATA::default()))
37106 }
37107 STATUSTEXT_DATA::ID => Some(Self::STATUSTEXT(STATUSTEXT_DATA::default())),
37108 STORAGE_INFORMATION_DATA::ID => Some(Self::STORAGE_INFORMATION(
37109 STORAGE_INFORMATION_DATA::default(),
37110 )),
37111 SUPPORTED_TUNES_DATA::ID => {
37112 Some(Self::SUPPORTED_TUNES(SUPPORTED_TUNES_DATA::default()))
37113 }
37114 SYSTEM_TIME_DATA::ID => Some(Self::SYSTEM_TIME(SYSTEM_TIME_DATA::default())),
37115 SYS_STATUS_DATA::ID => Some(Self::SYS_STATUS(SYS_STATUS_DATA::default())),
37116 TERRAIN_CHECK_DATA::ID => Some(Self::TERRAIN_CHECK(TERRAIN_CHECK_DATA::default())),
37117 TERRAIN_DATA_DATA::ID => Some(Self::TERRAIN_DATA(TERRAIN_DATA_DATA::default())),
37118 TERRAIN_REPORT_DATA::ID => Some(Self::TERRAIN_REPORT(TERRAIN_REPORT_DATA::default())),
37119 TERRAIN_REQUEST_DATA::ID => {
37120 Some(Self::TERRAIN_REQUEST(TERRAIN_REQUEST_DATA::default()))
37121 }
37122 TIMESYNC_DATA::ID => Some(Self::TIMESYNC(TIMESYNC_DATA::default())),
37123 TIME_ESTIMATE_TO_TARGET_DATA::ID => Some(Self::TIME_ESTIMATE_TO_TARGET(
37124 TIME_ESTIMATE_TO_TARGET_DATA::default(),
37125 )),
37126 TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID => {
37127 Some(Self::TRAJECTORY_REPRESENTATION_BEZIER(
37128 TRAJECTORY_REPRESENTATION_BEZIER_DATA::default(),
37129 ))
37130 }
37131 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID => {
37132 Some(Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(
37133 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::default(),
37134 ))
37135 }
37136 TUNNEL_DATA::ID => Some(Self::TUNNEL(TUNNEL_DATA::default())),
37137 UAVCAN_NODE_INFO_DATA::ID => {
37138 Some(Self::UAVCAN_NODE_INFO(UAVCAN_NODE_INFO_DATA::default()))
37139 }
37140 UAVCAN_NODE_STATUS_DATA::ID => {
37141 Some(Self::UAVCAN_NODE_STATUS(UAVCAN_NODE_STATUS_DATA::default()))
37142 }
37143 UTM_GLOBAL_POSITION_DATA::ID => Some(Self::UTM_GLOBAL_POSITION(
37144 UTM_GLOBAL_POSITION_DATA::default(),
37145 )),
37146 V2_EXTENSION_DATA::ID => Some(Self::V2_EXTENSION(V2_EXTENSION_DATA::default())),
37147 VFR_HUD_DATA::ID => Some(Self::VFR_HUD(VFR_HUD_DATA::default())),
37148 VIBRATION_DATA::ID => Some(Self::VIBRATION(VIBRATION_DATA::default())),
37149 VICON_POSITION_ESTIMATE_DATA::ID => Some(Self::VICON_POSITION_ESTIMATE(
37150 VICON_POSITION_ESTIMATE_DATA::default(),
37151 )),
37152 VIDEO_STREAM_INFORMATION_DATA::ID => Some(Self::VIDEO_STREAM_INFORMATION(
37153 VIDEO_STREAM_INFORMATION_DATA::default(),
37154 )),
37155 VIDEO_STREAM_STATUS_DATA::ID => Some(Self::VIDEO_STREAM_STATUS(
37156 VIDEO_STREAM_STATUS_DATA::default(),
37157 )),
37158 VISION_POSITION_ESTIMATE_DATA::ID => Some(Self::VISION_POSITION_ESTIMATE(
37159 VISION_POSITION_ESTIMATE_DATA::default(),
37160 )),
37161 VISION_SPEED_ESTIMATE_DATA::ID => Some(Self::VISION_SPEED_ESTIMATE(
37162 VISION_SPEED_ESTIMATE_DATA::default(),
37163 )),
37164 WHEEL_DISTANCE_DATA::ID => Some(Self::WHEEL_DISTANCE(WHEEL_DISTANCE_DATA::default())),
37165 WIFI_CONFIG_AP_DATA::ID => Some(Self::WIFI_CONFIG_AP(WIFI_CONFIG_AP_DATA::default())),
37166 WINCH_STATUS_DATA::ID => Some(Self::WINCH_STATUS(WINCH_STATUS_DATA::default())),
37167 WIND_COV_DATA::ID => Some(Self::WIND_COV(WIND_COV_DATA::default())),
37168 _ => None,
37169 }
37170 }
37171 #[cfg(feature = "arbitrary")]
37172 fn random_message_from_id<R: rand::RngCore>(id: u32, rng: &mut R) -> Option<Self> {
37173 match id {
37174 ACTUATOR_CONTROL_TARGET_DATA::ID => Some(Self::ACTUATOR_CONTROL_TARGET(
37175 ACTUATOR_CONTROL_TARGET_DATA::random(rng),
37176 )),
37177 ACTUATOR_OUTPUT_STATUS_DATA::ID => Some(Self::ACTUATOR_OUTPUT_STATUS(
37178 ACTUATOR_OUTPUT_STATUS_DATA::random(rng),
37179 )),
37180 ADSB_VEHICLE_DATA::ID => Some(Self::ADSB_VEHICLE(ADSB_VEHICLE_DATA::random(rng))),
37181 AIS_VESSEL_DATA::ID => Some(Self::AIS_VESSEL(AIS_VESSEL_DATA::random(rng))),
37182 ALTITUDE_DATA::ID => Some(Self::ALTITUDE(ALTITUDE_DATA::random(rng))),
37183 ATTITUDE_DATA::ID => Some(Self::ATTITUDE(ATTITUDE_DATA::random(rng))),
37184 ATTITUDE_QUATERNION_DATA::ID => Some(Self::ATTITUDE_QUATERNION(
37185 ATTITUDE_QUATERNION_DATA::random(rng),
37186 )),
37187 ATTITUDE_QUATERNION_COV_DATA::ID => Some(Self::ATTITUDE_QUATERNION_COV(
37188 ATTITUDE_QUATERNION_COV_DATA::random(rng),
37189 )),
37190 ATTITUDE_TARGET_DATA::ID => {
37191 Some(Self::ATTITUDE_TARGET(ATTITUDE_TARGET_DATA::random(rng)))
37192 }
37193 ATT_POS_MOCAP_DATA::ID => Some(Self::ATT_POS_MOCAP(ATT_POS_MOCAP_DATA::random(rng))),
37194 AUTH_KEY_DATA::ID => Some(Self::AUTH_KEY(AUTH_KEY_DATA::random(rng))),
37195 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID => {
37196 Some(Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(
37197 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::random(rng),
37198 ))
37199 }
37200 AUTOPILOT_VERSION_DATA::ID => {
37201 Some(Self::AUTOPILOT_VERSION(AUTOPILOT_VERSION_DATA::random(rng)))
37202 }
37203 AVAILABLE_MODES_DATA::ID => {
37204 Some(Self::AVAILABLE_MODES(AVAILABLE_MODES_DATA::random(rng)))
37205 }
37206 AVAILABLE_MODES_MONITOR_DATA::ID => Some(Self::AVAILABLE_MODES_MONITOR(
37207 AVAILABLE_MODES_MONITOR_DATA::random(rng),
37208 )),
37209 BATTERY_INFO_DATA::ID => Some(Self::BATTERY_INFO(BATTERY_INFO_DATA::random(rng))),
37210 BATTERY_STATUS_DATA::ID => Some(Self::BATTERY_STATUS(BATTERY_STATUS_DATA::random(rng))),
37211 BUTTON_CHANGE_DATA::ID => Some(Self::BUTTON_CHANGE(BUTTON_CHANGE_DATA::random(rng))),
37212 CAMERA_CAPTURE_STATUS_DATA::ID => Some(Self::CAMERA_CAPTURE_STATUS(
37213 CAMERA_CAPTURE_STATUS_DATA::random(rng),
37214 )),
37215 CAMERA_FOV_STATUS_DATA::ID => {
37216 Some(Self::CAMERA_FOV_STATUS(CAMERA_FOV_STATUS_DATA::random(rng)))
37217 }
37218 CAMERA_IMAGE_CAPTURED_DATA::ID => Some(Self::CAMERA_IMAGE_CAPTURED(
37219 CAMERA_IMAGE_CAPTURED_DATA::random(rng),
37220 )),
37221 CAMERA_INFORMATION_DATA::ID => Some(Self::CAMERA_INFORMATION(
37222 CAMERA_INFORMATION_DATA::random(rng),
37223 )),
37224 CAMERA_SETTINGS_DATA::ID => {
37225 Some(Self::CAMERA_SETTINGS(CAMERA_SETTINGS_DATA::random(rng)))
37226 }
37227 CAMERA_THERMAL_RANGE_DATA::ID => Some(Self::CAMERA_THERMAL_RANGE(
37228 CAMERA_THERMAL_RANGE_DATA::random(rng),
37229 )),
37230 CAMERA_TRACKING_GEO_STATUS_DATA::ID => Some(Self::CAMERA_TRACKING_GEO_STATUS(
37231 CAMERA_TRACKING_GEO_STATUS_DATA::random(rng),
37232 )),
37233 CAMERA_TRACKING_IMAGE_STATUS_DATA::ID => Some(Self::CAMERA_TRACKING_IMAGE_STATUS(
37234 CAMERA_TRACKING_IMAGE_STATUS_DATA::random(rng),
37235 )),
37236 CAMERA_TRIGGER_DATA::ID => Some(Self::CAMERA_TRIGGER(CAMERA_TRIGGER_DATA::random(rng))),
37237 CANFD_FRAME_DATA::ID => Some(Self::CANFD_FRAME(CANFD_FRAME_DATA::random(rng))),
37238 CAN_FILTER_MODIFY_DATA::ID => {
37239 Some(Self::CAN_FILTER_MODIFY(CAN_FILTER_MODIFY_DATA::random(rng)))
37240 }
37241 CAN_FRAME_DATA::ID => Some(Self::CAN_FRAME(CAN_FRAME_DATA::random(rng))),
37242 CELLULAR_CONFIG_DATA::ID => {
37243 Some(Self::CELLULAR_CONFIG(CELLULAR_CONFIG_DATA::random(rng)))
37244 }
37245 CELLULAR_STATUS_DATA::ID => {
37246 Some(Self::CELLULAR_STATUS(CELLULAR_STATUS_DATA::random(rng)))
37247 }
37248 CHANGE_OPERATOR_CONTROL_DATA::ID => Some(Self::CHANGE_OPERATOR_CONTROL(
37249 CHANGE_OPERATOR_CONTROL_DATA::random(rng),
37250 )),
37251 CHANGE_OPERATOR_CONTROL_ACK_DATA::ID => Some(Self::CHANGE_OPERATOR_CONTROL_ACK(
37252 CHANGE_OPERATOR_CONTROL_ACK_DATA::random(rng),
37253 )),
37254 COLLISION_DATA::ID => Some(Self::COLLISION(COLLISION_DATA::random(rng))),
37255 COMMAND_ACK_DATA::ID => Some(Self::COMMAND_ACK(COMMAND_ACK_DATA::random(rng))),
37256 COMMAND_CANCEL_DATA::ID => Some(Self::COMMAND_CANCEL(COMMAND_CANCEL_DATA::random(rng))),
37257 COMMAND_INT_DATA::ID => Some(Self::COMMAND_INT(COMMAND_INT_DATA::random(rng))),
37258 COMMAND_LONG_DATA::ID => Some(Self::COMMAND_LONG(COMMAND_LONG_DATA::random(rng))),
37259 COMPONENT_INFORMATION_DATA::ID => Some(Self::COMPONENT_INFORMATION(
37260 COMPONENT_INFORMATION_DATA::random(rng),
37261 )),
37262 COMPONENT_INFORMATION_BASIC_DATA::ID => Some(Self::COMPONENT_INFORMATION_BASIC(
37263 COMPONENT_INFORMATION_BASIC_DATA::random(rng),
37264 )),
37265 COMPONENT_METADATA_DATA::ID => Some(Self::COMPONENT_METADATA(
37266 COMPONENT_METADATA_DATA::random(rng),
37267 )),
37268 CONTROL_SYSTEM_STATE_DATA::ID => Some(Self::CONTROL_SYSTEM_STATE(
37269 CONTROL_SYSTEM_STATE_DATA::random(rng),
37270 )),
37271 CURRENT_EVENT_SEQUENCE_DATA::ID => Some(Self::CURRENT_EVENT_SEQUENCE(
37272 CURRENT_EVENT_SEQUENCE_DATA::random(rng),
37273 )),
37274 CURRENT_MODE_DATA::ID => Some(Self::CURRENT_MODE(CURRENT_MODE_DATA::random(rng))),
37275 DATA_STREAM_DATA::ID => Some(Self::DATA_STREAM(DATA_STREAM_DATA::random(rng))),
37276 DATA_TRANSMISSION_HANDSHAKE_DATA::ID => Some(Self::DATA_TRANSMISSION_HANDSHAKE(
37277 DATA_TRANSMISSION_HANDSHAKE_DATA::random(rng),
37278 )),
37279 DEBUG_DATA::ID => Some(Self::DEBUG(DEBUG_DATA::random(rng))),
37280 DEBUG_FLOAT_ARRAY_DATA::ID => {
37281 Some(Self::DEBUG_FLOAT_ARRAY(DEBUG_FLOAT_ARRAY_DATA::random(rng)))
37282 }
37283 DEBUG_VECT_DATA::ID => Some(Self::DEBUG_VECT(DEBUG_VECT_DATA::random(rng))),
37284 DISTANCE_SENSOR_DATA::ID => {
37285 Some(Self::DISTANCE_SENSOR(DISTANCE_SENSOR_DATA::random(rng)))
37286 }
37287 EFI_STATUS_DATA::ID => Some(Self::EFI_STATUS(EFI_STATUS_DATA::random(rng))),
37288 ENCAPSULATED_DATA_DATA::ID => {
37289 Some(Self::ENCAPSULATED_DATA(ENCAPSULATED_DATA_DATA::random(rng)))
37290 }
37291 ESC_INFO_DATA::ID => Some(Self::ESC_INFO(ESC_INFO_DATA::random(rng))),
37292 ESC_STATUS_DATA::ID => Some(Self::ESC_STATUS(ESC_STATUS_DATA::random(rng))),
37293 ESTIMATOR_STATUS_DATA::ID => {
37294 Some(Self::ESTIMATOR_STATUS(ESTIMATOR_STATUS_DATA::random(rng)))
37295 }
37296 EVENT_DATA::ID => Some(Self::EVENT(EVENT_DATA::random(rng))),
37297 EXTENDED_SYS_STATE_DATA::ID => Some(Self::EXTENDED_SYS_STATE(
37298 EXTENDED_SYS_STATE_DATA::random(rng),
37299 )),
37300 FENCE_STATUS_DATA::ID => Some(Self::FENCE_STATUS(FENCE_STATUS_DATA::random(rng))),
37301 FILE_TRANSFER_PROTOCOL_DATA::ID => Some(Self::FILE_TRANSFER_PROTOCOL(
37302 FILE_TRANSFER_PROTOCOL_DATA::random(rng),
37303 )),
37304 FLIGHT_INFORMATION_DATA::ID => Some(Self::FLIGHT_INFORMATION(
37305 FLIGHT_INFORMATION_DATA::random(rng),
37306 )),
37307 FOLLOW_TARGET_DATA::ID => Some(Self::FOLLOW_TARGET(FOLLOW_TARGET_DATA::random(rng))),
37308 FUEL_STATUS_DATA::ID => Some(Self::FUEL_STATUS(FUEL_STATUS_DATA::random(rng))),
37309 GENERATOR_STATUS_DATA::ID => {
37310 Some(Self::GENERATOR_STATUS(GENERATOR_STATUS_DATA::random(rng)))
37311 }
37312 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID => Some(Self::GIMBAL_DEVICE_ATTITUDE_STATUS(
37313 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::random(rng),
37314 )),
37315 GIMBAL_DEVICE_INFORMATION_DATA::ID => Some(Self::GIMBAL_DEVICE_INFORMATION(
37316 GIMBAL_DEVICE_INFORMATION_DATA::random(rng),
37317 )),
37318 GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID => Some(Self::GIMBAL_DEVICE_SET_ATTITUDE(
37319 GIMBAL_DEVICE_SET_ATTITUDE_DATA::random(rng),
37320 )),
37321 GIMBAL_MANAGER_INFORMATION_DATA::ID => Some(Self::GIMBAL_MANAGER_INFORMATION(
37322 GIMBAL_MANAGER_INFORMATION_DATA::random(rng),
37323 )),
37324 GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID => Some(Self::GIMBAL_MANAGER_SET_ATTITUDE(
37325 GIMBAL_MANAGER_SET_ATTITUDE_DATA::random(rng),
37326 )),
37327 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID => {
37328 Some(Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(
37329 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::random(rng),
37330 ))
37331 }
37332 GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID => Some(Self::GIMBAL_MANAGER_SET_PITCHYAW(
37333 GIMBAL_MANAGER_SET_PITCHYAW_DATA::random(rng),
37334 )),
37335 GIMBAL_MANAGER_STATUS_DATA::ID => Some(Self::GIMBAL_MANAGER_STATUS(
37336 GIMBAL_MANAGER_STATUS_DATA::random(rng),
37337 )),
37338 GLOBAL_POSITION_INT_DATA::ID => Some(Self::GLOBAL_POSITION_INT(
37339 GLOBAL_POSITION_INT_DATA::random(rng),
37340 )),
37341 GLOBAL_POSITION_INT_COV_DATA::ID => Some(Self::GLOBAL_POSITION_INT_COV(
37342 GLOBAL_POSITION_INT_COV_DATA::random(rng),
37343 )),
37344 GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID => {
37345 Some(Self::GLOBAL_VISION_POSITION_ESTIMATE(
37346 GLOBAL_VISION_POSITION_ESTIMATE_DATA::random(rng),
37347 ))
37348 }
37349 GPS2_RAW_DATA::ID => Some(Self::GPS2_RAW(GPS2_RAW_DATA::random(rng))),
37350 GPS2_RTK_DATA::ID => Some(Self::GPS2_RTK(GPS2_RTK_DATA::random(rng))),
37351 GPS_GLOBAL_ORIGIN_DATA::ID => {
37352 Some(Self::GPS_GLOBAL_ORIGIN(GPS_GLOBAL_ORIGIN_DATA::random(rng)))
37353 }
37354 GPS_INJECT_DATA_DATA::ID => {
37355 Some(Self::GPS_INJECT_DATA(GPS_INJECT_DATA_DATA::random(rng)))
37356 }
37357 GPS_INPUT_DATA::ID => Some(Self::GPS_INPUT(GPS_INPUT_DATA::random(rng))),
37358 GPS_RAW_INT_DATA::ID => Some(Self::GPS_RAW_INT(GPS_RAW_INT_DATA::random(rng))),
37359 GPS_RTCM_DATA_DATA::ID => Some(Self::GPS_RTCM_DATA(GPS_RTCM_DATA_DATA::random(rng))),
37360 GPS_RTK_DATA::ID => Some(Self::GPS_RTK(GPS_RTK_DATA::random(rng))),
37361 GPS_STATUS_DATA::ID => Some(Self::GPS_STATUS(GPS_STATUS_DATA::random(rng))),
37362 HEARTBEAT_DATA::ID => Some(Self::HEARTBEAT(HEARTBEAT_DATA::random(rng))),
37363 HIGHRES_IMU_DATA::ID => Some(Self::HIGHRES_IMU(HIGHRES_IMU_DATA::random(rng))),
37364 HIGH_LATENCY_DATA::ID => Some(Self::HIGH_LATENCY(HIGH_LATENCY_DATA::random(rng))),
37365 HIGH_LATENCY2_DATA::ID => Some(Self::HIGH_LATENCY2(HIGH_LATENCY2_DATA::random(rng))),
37366 HIL_ACTUATOR_CONTROLS_DATA::ID => Some(Self::HIL_ACTUATOR_CONTROLS(
37367 HIL_ACTUATOR_CONTROLS_DATA::random(rng),
37368 )),
37369 HIL_CONTROLS_DATA::ID => Some(Self::HIL_CONTROLS(HIL_CONTROLS_DATA::random(rng))),
37370 HIL_GPS_DATA::ID => Some(Self::HIL_GPS(HIL_GPS_DATA::random(rng))),
37371 HIL_OPTICAL_FLOW_DATA::ID => {
37372 Some(Self::HIL_OPTICAL_FLOW(HIL_OPTICAL_FLOW_DATA::random(rng)))
37373 }
37374 HIL_RC_INPUTS_RAW_DATA::ID => {
37375 Some(Self::HIL_RC_INPUTS_RAW(HIL_RC_INPUTS_RAW_DATA::random(rng)))
37376 }
37377 HIL_SENSOR_DATA::ID => Some(Self::HIL_SENSOR(HIL_SENSOR_DATA::random(rng))),
37378 HIL_STATE_DATA::ID => Some(Self::HIL_STATE(HIL_STATE_DATA::random(rng))),
37379 HIL_STATE_QUATERNION_DATA::ID => Some(Self::HIL_STATE_QUATERNION(
37380 HIL_STATE_QUATERNION_DATA::random(rng),
37381 )),
37382 HOME_POSITION_DATA::ID => Some(Self::HOME_POSITION(HOME_POSITION_DATA::random(rng))),
37383 HYGROMETER_SENSOR_DATA::ID => {
37384 Some(Self::HYGROMETER_SENSOR(HYGROMETER_SENSOR_DATA::random(rng)))
37385 }
37386 ILLUMINATOR_STATUS_DATA::ID => Some(Self::ILLUMINATOR_STATUS(
37387 ILLUMINATOR_STATUS_DATA::random(rng),
37388 )),
37389 ISBD_LINK_STATUS_DATA::ID => {
37390 Some(Self::ISBD_LINK_STATUS(ISBD_LINK_STATUS_DATA::random(rng)))
37391 }
37392 LANDING_TARGET_DATA::ID => Some(Self::LANDING_TARGET(LANDING_TARGET_DATA::random(rng))),
37393 LINK_NODE_STATUS_DATA::ID => {
37394 Some(Self::LINK_NODE_STATUS(LINK_NODE_STATUS_DATA::random(rng)))
37395 }
37396 LOCAL_POSITION_NED_DATA::ID => Some(Self::LOCAL_POSITION_NED(
37397 LOCAL_POSITION_NED_DATA::random(rng),
37398 )),
37399 LOCAL_POSITION_NED_COV_DATA::ID => Some(Self::LOCAL_POSITION_NED_COV(
37400 LOCAL_POSITION_NED_COV_DATA::random(rng),
37401 )),
37402 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID => {
37403 Some(Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(
37404 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::random(rng),
37405 ))
37406 }
37407 LOGGING_ACK_DATA::ID => Some(Self::LOGGING_ACK(LOGGING_ACK_DATA::random(rng))),
37408 LOGGING_DATA_DATA::ID => Some(Self::LOGGING_DATA(LOGGING_DATA_DATA::random(rng))),
37409 LOGGING_DATA_ACKED_DATA::ID => Some(Self::LOGGING_DATA_ACKED(
37410 LOGGING_DATA_ACKED_DATA::random(rng),
37411 )),
37412 LOG_DATA_DATA::ID => Some(Self::LOG_DATA(LOG_DATA_DATA::random(rng))),
37413 LOG_ENTRY_DATA::ID => Some(Self::LOG_ENTRY(LOG_ENTRY_DATA::random(rng))),
37414 LOG_ERASE_DATA::ID => Some(Self::LOG_ERASE(LOG_ERASE_DATA::random(rng))),
37415 LOG_REQUEST_DATA_DATA::ID => {
37416 Some(Self::LOG_REQUEST_DATA(LOG_REQUEST_DATA_DATA::random(rng)))
37417 }
37418 LOG_REQUEST_END_DATA::ID => {
37419 Some(Self::LOG_REQUEST_END(LOG_REQUEST_END_DATA::random(rng)))
37420 }
37421 LOG_REQUEST_LIST_DATA::ID => {
37422 Some(Self::LOG_REQUEST_LIST(LOG_REQUEST_LIST_DATA::random(rng)))
37423 }
37424 MAG_CAL_REPORT_DATA::ID => Some(Self::MAG_CAL_REPORT(MAG_CAL_REPORT_DATA::random(rng))),
37425 MANUAL_CONTROL_DATA::ID => Some(Self::MANUAL_CONTROL(MANUAL_CONTROL_DATA::random(rng))),
37426 MANUAL_SETPOINT_DATA::ID => {
37427 Some(Self::MANUAL_SETPOINT(MANUAL_SETPOINT_DATA::random(rng)))
37428 }
37429 MEMORY_VECT_DATA::ID => Some(Self::MEMORY_VECT(MEMORY_VECT_DATA::random(rng))),
37430 MESSAGE_INTERVAL_DATA::ID => {
37431 Some(Self::MESSAGE_INTERVAL(MESSAGE_INTERVAL_DATA::random(rng)))
37432 }
37433 MISSION_ACK_DATA::ID => Some(Self::MISSION_ACK(MISSION_ACK_DATA::random(rng))),
37434 MISSION_CLEAR_ALL_DATA::ID => {
37435 Some(Self::MISSION_CLEAR_ALL(MISSION_CLEAR_ALL_DATA::random(rng)))
37436 }
37437 MISSION_COUNT_DATA::ID => Some(Self::MISSION_COUNT(MISSION_COUNT_DATA::random(rng))),
37438 MISSION_CURRENT_DATA::ID => {
37439 Some(Self::MISSION_CURRENT(MISSION_CURRENT_DATA::random(rng)))
37440 }
37441 MISSION_ITEM_DATA::ID => Some(Self::MISSION_ITEM(MISSION_ITEM_DATA::random(rng))),
37442 MISSION_ITEM_INT_DATA::ID => {
37443 Some(Self::MISSION_ITEM_INT(MISSION_ITEM_INT_DATA::random(rng)))
37444 }
37445 MISSION_ITEM_REACHED_DATA::ID => Some(Self::MISSION_ITEM_REACHED(
37446 MISSION_ITEM_REACHED_DATA::random(rng),
37447 )),
37448 MISSION_REQUEST_DATA::ID => {
37449 Some(Self::MISSION_REQUEST(MISSION_REQUEST_DATA::random(rng)))
37450 }
37451 MISSION_REQUEST_INT_DATA::ID => Some(Self::MISSION_REQUEST_INT(
37452 MISSION_REQUEST_INT_DATA::random(rng),
37453 )),
37454 MISSION_REQUEST_LIST_DATA::ID => Some(Self::MISSION_REQUEST_LIST(
37455 MISSION_REQUEST_LIST_DATA::random(rng),
37456 )),
37457 MISSION_REQUEST_PARTIAL_LIST_DATA::ID => Some(Self::MISSION_REQUEST_PARTIAL_LIST(
37458 MISSION_REQUEST_PARTIAL_LIST_DATA::random(rng),
37459 )),
37460 MISSION_SET_CURRENT_DATA::ID => Some(Self::MISSION_SET_CURRENT(
37461 MISSION_SET_CURRENT_DATA::random(rng),
37462 )),
37463 MISSION_WRITE_PARTIAL_LIST_DATA::ID => Some(Self::MISSION_WRITE_PARTIAL_LIST(
37464 MISSION_WRITE_PARTIAL_LIST_DATA::random(rng),
37465 )),
37466 MOUNT_ORIENTATION_DATA::ID => {
37467 Some(Self::MOUNT_ORIENTATION(MOUNT_ORIENTATION_DATA::random(rng)))
37468 }
37469 NAMED_VALUE_FLOAT_DATA::ID => {
37470 Some(Self::NAMED_VALUE_FLOAT(NAMED_VALUE_FLOAT_DATA::random(rng)))
37471 }
37472 NAMED_VALUE_INT_DATA::ID => {
37473 Some(Self::NAMED_VALUE_INT(NAMED_VALUE_INT_DATA::random(rng)))
37474 }
37475 NAV_CONTROLLER_OUTPUT_DATA::ID => Some(Self::NAV_CONTROLLER_OUTPUT(
37476 NAV_CONTROLLER_OUTPUT_DATA::random(rng),
37477 )),
37478 OBSTACLE_DISTANCE_DATA::ID => {
37479 Some(Self::OBSTACLE_DISTANCE(OBSTACLE_DISTANCE_DATA::random(rng)))
37480 }
37481 ODOMETRY_DATA::ID => Some(Self::ODOMETRY(ODOMETRY_DATA::random(rng))),
37482 ONBOARD_COMPUTER_STATUS_DATA::ID => Some(Self::ONBOARD_COMPUTER_STATUS(
37483 ONBOARD_COMPUTER_STATUS_DATA::random(rng),
37484 )),
37485 OPEN_DRONE_ID_ARM_STATUS_DATA::ID => Some(Self::OPEN_DRONE_ID_ARM_STATUS(
37486 OPEN_DRONE_ID_ARM_STATUS_DATA::random(rng),
37487 )),
37488 OPEN_DRONE_ID_AUTHENTICATION_DATA::ID => Some(Self::OPEN_DRONE_ID_AUTHENTICATION(
37489 OPEN_DRONE_ID_AUTHENTICATION_DATA::random(rng),
37490 )),
37491 OPEN_DRONE_ID_BASIC_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_BASIC_ID(
37492 OPEN_DRONE_ID_BASIC_ID_DATA::random(rng),
37493 )),
37494 OPEN_DRONE_ID_LOCATION_DATA::ID => Some(Self::OPEN_DRONE_ID_LOCATION(
37495 OPEN_DRONE_ID_LOCATION_DATA::random(rng),
37496 )),
37497 OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID => Some(Self::OPEN_DRONE_ID_MESSAGE_PACK(
37498 OPEN_DRONE_ID_MESSAGE_PACK_DATA::random(rng),
37499 )),
37500 OPEN_DRONE_ID_OPERATOR_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_OPERATOR_ID(
37501 OPEN_DRONE_ID_OPERATOR_ID_DATA::random(rng),
37502 )),
37503 OPEN_DRONE_ID_SELF_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_SELF_ID(
37504 OPEN_DRONE_ID_SELF_ID_DATA::random(rng),
37505 )),
37506 OPEN_DRONE_ID_SYSTEM_DATA::ID => Some(Self::OPEN_DRONE_ID_SYSTEM(
37507 OPEN_DRONE_ID_SYSTEM_DATA::random(rng),
37508 )),
37509 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID => Some(Self::OPEN_DRONE_ID_SYSTEM_UPDATE(
37510 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::random(rng),
37511 )),
37512 OPTICAL_FLOW_DATA::ID => Some(Self::OPTICAL_FLOW(OPTICAL_FLOW_DATA::random(rng))),
37513 OPTICAL_FLOW_RAD_DATA::ID => {
37514 Some(Self::OPTICAL_FLOW_RAD(OPTICAL_FLOW_RAD_DATA::random(rng)))
37515 }
37516 ORBIT_EXECUTION_STATUS_DATA::ID => Some(Self::ORBIT_EXECUTION_STATUS(
37517 ORBIT_EXECUTION_STATUS_DATA::random(rng),
37518 )),
37519 PARAM_EXT_ACK_DATA::ID => Some(Self::PARAM_EXT_ACK(PARAM_EXT_ACK_DATA::random(rng))),
37520 PARAM_EXT_REQUEST_LIST_DATA::ID => Some(Self::PARAM_EXT_REQUEST_LIST(
37521 PARAM_EXT_REQUEST_LIST_DATA::random(rng),
37522 )),
37523 PARAM_EXT_REQUEST_READ_DATA::ID => Some(Self::PARAM_EXT_REQUEST_READ(
37524 PARAM_EXT_REQUEST_READ_DATA::random(rng),
37525 )),
37526 PARAM_EXT_SET_DATA::ID => Some(Self::PARAM_EXT_SET(PARAM_EXT_SET_DATA::random(rng))),
37527 PARAM_EXT_VALUE_DATA::ID => {
37528 Some(Self::PARAM_EXT_VALUE(PARAM_EXT_VALUE_DATA::random(rng)))
37529 }
37530 PARAM_MAP_RC_DATA::ID => Some(Self::PARAM_MAP_RC(PARAM_MAP_RC_DATA::random(rng))),
37531 PARAM_REQUEST_LIST_DATA::ID => Some(Self::PARAM_REQUEST_LIST(
37532 PARAM_REQUEST_LIST_DATA::random(rng),
37533 )),
37534 PARAM_REQUEST_READ_DATA::ID => Some(Self::PARAM_REQUEST_READ(
37535 PARAM_REQUEST_READ_DATA::random(rng),
37536 )),
37537 PARAM_SET_DATA::ID => Some(Self::PARAM_SET(PARAM_SET_DATA::random(rng))),
37538 PARAM_VALUE_DATA::ID => Some(Self::PARAM_VALUE(PARAM_VALUE_DATA::random(rng))),
37539 PING_DATA::ID => Some(Self::PING(PING_DATA::random(rng))),
37540 PLAY_TUNE_DATA::ID => Some(Self::PLAY_TUNE(PLAY_TUNE_DATA::random(rng))),
37541 PLAY_TUNE_V2_DATA::ID => Some(Self::PLAY_TUNE_V2(PLAY_TUNE_V2_DATA::random(rng))),
37542 POSITION_TARGET_GLOBAL_INT_DATA::ID => Some(Self::POSITION_TARGET_GLOBAL_INT(
37543 POSITION_TARGET_GLOBAL_INT_DATA::random(rng),
37544 )),
37545 POSITION_TARGET_LOCAL_NED_DATA::ID => Some(Self::POSITION_TARGET_LOCAL_NED(
37546 POSITION_TARGET_LOCAL_NED_DATA::random(rng),
37547 )),
37548 POWER_STATUS_DATA::ID => Some(Self::POWER_STATUS(POWER_STATUS_DATA::random(rng))),
37549 PROTOCOL_VERSION_DATA::ID => {
37550 Some(Self::PROTOCOL_VERSION(PROTOCOL_VERSION_DATA::random(rng)))
37551 }
37552 RADIO_STATUS_DATA::ID => Some(Self::RADIO_STATUS(RADIO_STATUS_DATA::random(rng))),
37553 RAW_IMU_DATA::ID => Some(Self::RAW_IMU(RAW_IMU_DATA::random(rng))),
37554 RAW_PRESSURE_DATA::ID => Some(Self::RAW_PRESSURE(RAW_PRESSURE_DATA::random(rng))),
37555 RAW_RPM_DATA::ID => Some(Self::RAW_RPM(RAW_RPM_DATA::random(rng))),
37556 RC_CHANNELS_DATA::ID => Some(Self::RC_CHANNELS(RC_CHANNELS_DATA::random(rng))),
37557 RC_CHANNELS_OVERRIDE_DATA::ID => Some(Self::RC_CHANNELS_OVERRIDE(
37558 RC_CHANNELS_OVERRIDE_DATA::random(rng),
37559 )),
37560 RC_CHANNELS_RAW_DATA::ID => {
37561 Some(Self::RC_CHANNELS_RAW(RC_CHANNELS_RAW_DATA::random(rng)))
37562 }
37563 RC_CHANNELS_SCALED_DATA::ID => Some(Self::RC_CHANNELS_SCALED(
37564 RC_CHANNELS_SCALED_DATA::random(rng),
37565 )),
37566 REQUEST_DATA_STREAM_DATA::ID => Some(Self::REQUEST_DATA_STREAM(
37567 REQUEST_DATA_STREAM_DATA::random(rng),
37568 )),
37569 REQUEST_EVENT_DATA::ID => Some(Self::REQUEST_EVENT(REQUEST_EVENT_DATA::random(rng))),
37570 RESOURCE_REQUEST_DATA::ID => {
37571 Some(Self::RESOURCE_REQUEST(RESOURCE_REQUEST_DATA::random(rng)))
37572 }
37573 RESPONSE_EVENT_ERROR_DATA::ID => Some(Self::RESPONSE_EVENT_ERROR(
37574 RESPONSE_EVENT_ERROR_DATA::random(rng),
37575 )),
37576 SAFETY_ALLOWED_AREA_DATA::ID => Some(Self::SAFETY_ALLOWED_AREA(
37577 SAFETY_ALLOWED_AREA_DATA::random(rng),
37578 )),
37579 SAFETY_SET_ALLOWED_AREA_DATA::ID => Some(Self::SAFETY_SET_ALLOWED_AREA(
37580 SAFETY_SET_ALLOWED_AREA_DATA::random(rng),
37581 )),
37582 SCALED_IMU_DATA::ID => Some(Self::SCALED_IMU(SCALED_IMU_DATA::random(rng))),
37583 SCALED_IMU2_DATA::ID => Some(Self::SCALED_IMU2(SCALED_IMU2_DATA::random(rng))),
37584 SCALED_IMU3_DATA::ID => Some(Self::SCALED_IMU3(SCALED_IMU3_DATA::random(rng))),
37585 SCALED_PRESSURE_DATA::ID => {
37586 Some(Self::SCALED_PRESSURE(SCALED_PRESSURE_DATA::random(rng)))
37587 }
37588 SCALED_PRESSURE2_DATA::ID => {
37589 Some(Self::SCALED_PRESSURE2(SCALED_PRESSURE2_DATA::random(rng)))
37590 }
37591 SCALED_PRESSURE3_DATA::ID => {
37592 Some(Self::SCALED_PRESSURE3(SCALED_PRESSURE3_DATA::random(rng)))
37593 }
37594 SERIAL_CONTROL_DATA::ID => Some(Self::SERIAL_CONTROL(SERIAL_CONTROL_DATA::random(rng))),
37595 SERVO_OUTPUT_RAW_DATA::ID => {
37596 Some(Self::SERVO_OUTPUT_RAW(SERVO_OUTPUT_RAW_DATA::random(rng)))
37597 }
37598 SETUP_SIGNING_DATA::ID => Some(Self::SETUP_SIGNING(SETUP_SIGNING_DATA::random(rng))),
37599 SET_ACTUATOR_CONTROL_TARGET_DATA::ID => Some(Self::SET_ACTUATOR_CONTROL_TARGET(
37600 SET_ACTUATOR_CONTROL_TARGET_DATA::random(rng),
37601 )),
37602 SET_ATTITUDE_TARGET_DATA::ID => Some(Self::SET_ATTITUDE_TARGET(
37603 SET_ATTITUDE_TARGET_DATA::random(rng),
37604 )),
37605 SET_GPS_GLOBAL_ORIGIN_DATA::ID => Some(Self::SET_GPS_GLOBAL_ORIGIN(
37606 SET_GPS_GLOBAL_ORIGIN_DATA::random(rng),
37607 )),
37608 SET_HOME_POSITION_DATA::ID => {
37609 Some(Self::SET_HOME_POSITION(SET_HOME_POSITION_DATA::random(rng)))
37610 }
37611 SET_MODE_DATA::ID => Some(Self::SET_MODE(SET_MODE_DATA::random(rng))),
37612 SET_POSITION_TARGET_GLOBAL_INT_DATA::ID => Some(Self::SET_POSITION_TARGET_GLOBAL_INT(
37613 SET_POSITION_TARGET_GLOBAL_INT_DATA::random(rng),
37614 )),
37615 SET_POSITION_TARGET_LOCAL_NED_DATA::ID => Some(Self::SET_POSITION_TARGET_LOCAL_NED(
37616 SET_POSITION_TARGET_LOCAL_NED_DATA::random(rng),
37617 )),
37618 SIM_STATE_DATA::ID => Some(Self::SIM_STATE(SIM_STATE_DATA::random(rng))),
37619 SMART_BATTERY_INFO_DATA::ID => Some(Self::SMART_BATTERY_INFO(
37620 SMART_BATTERY_INFO_DATA::random(rng),
37621 )),
37622 STATUSTEXT_DATA::ID => Some(Self::STATUSTEXT(STATUSTEXT_DATA::random(rng))),
37623 STORAGE_INFORMATION_DATA::ID => Some(Self::STORAGE_INFORMATION(
37624 STORAGE_INFORMATION_DATA::random(rng),
37625 )),
37626 SUPPORTED_TUNES_DATA::ID => {
37627 Some(Self::SUPPORTED_TUNES(SUPPORTED_TUNES_DATA::random(rng)))
37628 }
37629 SYSTEM_TIME_DATA::ID => Some(Self::SYSTEM_TIME(SYSTEM_TIME_DATA::random(rng))),
37630 SYS_STATUS_DATA::ID => Some(Self::SYS_STATUS(SYS_STATUS_DATA::random(rng))),
37631 TERRAIN_CHECK_DATA::ID => Some(Self::TERRAIN_CHECK(TERRAIN_CHECK_DATA::random(rng))),
37632 TERRAIN_DATA_DATA::ID => Some(Self::TERRAIN_DATA(TERRAIN_DATA_DATA::random(rng))),
37633 TERRAIN_REPORT_DATA::ID => Some(Self::TERRAIN_REPORT(TERRAIN_REPORT_DATA::random(rng))),
37634 TERRAIN_REQUEST_DATA::ID => {
37635 Some(Self::TERRAIN_REQUEST(TERRAIN_REQUEST_DATA::random(rng)))
37636 }
37637 TIMESYNC_DATA::ID => Some(Self::TIMESYNC(TIMESYNC_DATA::random(rng))),
37638 TIME_ESTIMATE_TO_TARGET_DATA::ID => Some(Self::TIME_ESTIMATE_TO_TARGET(
37639 TIME_ESTIMATE_TO_TARGET_DATA::random(rng),
37640 )),
37641 TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID => {
37642 Some(Self::TRAJECTORY_REPRESENTATION_BEZIER(
37643 TRAJECTORY_REPRESENTATION_BEZIER_DATA::random(rng),
37644 ))
37645 }
37646 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID => {
37647 Some(Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(
37648 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::random(rng),
37649 ))
37650 }
37651 TUNNEL_DATA::ID => Some(Self::TUNNEL(TUNNEL_DATA::random(rng))),
37652 UAVCAN_NODE_INFO_DATA::ID => {
37653 Some(Self::UAVCAN_NODE_INFO(UAVCAN_NODE_INFO_DATA::random(rng)))
37654 }
37655 UAVCAN_NODE_STATUS_DATA::ID => Some(Self::UAVCAN_NODE_STATUS(
37656 UAVCAN_NODE_STATUS_DATA::random(rng),
37657 )),
37658 UTM_GLOBAL_POSITION_DATA::ID => Some(Self::UTM_GLOBAL_POSITION(
37659 UTM_GLOBAL_POSITION_DATA::random(rng),
37660 )),
37661 V2_EXTENSION_DATA::ID => Some(Self::V2_EXTENSION(V2_EXTENSION_DATA::random(rng))),
37662 VFR_HUD_DATA::ID => Some(Self::VFR_HUD(VFR_HUD_DATA::random(rng))),
37663 VIBRATION_DATA::ID => Some(Self::VIBRATION(VIBRATION_DATA::random(rng))),
37664 VICON_POSITION_ESTIMATE_DATA::ID => Some(Self::VICON_POSITION_ESTIMATE(
37665 VICON_POSITION_ESTIMATE_DATA::random(rng),
37666 )),
37667 VIDEO_STREAM_INFORMATION_DATA::ID => Some(Self::VIDEO_STREAM_INFORMATION(
37668 VIDEO_STREAM_INFORMATION_DATA::random(rng),
37669 )),
37670 VIDEO_STREAM_STATUS_DATA::ID => Some(Self::VIDEO_STREAM_STATUS(
37671 VIDEO_STREAM_STATUS_DATA::random(rng),
37672 )),
37673 VISION_POSITION_ESTIMATE_DATA::ID => Some(Self::VISION_POSITION_ESTIMATE(
37674 VISION_POSITION_ESTIMATE_DATA::random(rng),
37675 )),
37676 VISION_SPEED_ESTIMATE_DATA::ID => Some(Self::VISION_SPEED_ESTIMATE(
37677 VISION_SPEED_ESTIMATE_DATA::random(rng),
37678 )),
37679 WHEEL_DISTANCE_DATA::ID => Some(Self::WHEEL_DISTANCE(WHEEL_DISTANCE_DATA::random(rng))),
37680 WIFI_CONFIG_AP_DATA::ID => Some(Self::WIFI_CONFIG_AP(WIFI_CONFIG_AP_DATA::random(rng))),
37681 WINCH_STATUS_DATA::ID => Some(Self::WINCH_STATUS(WINCH_STATUS_DATA::random(rng))),
37682 WIND_COV_DATA::ID => Some(Self::WIND_COV(WIND_COV_DATA::random(rng))),
37683 _ => None,
37684 }
37685 }
37686 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
37687 match self {
37688 Self::ACTUATOR_CONTROL_TARGET(body) => body.ser(version, bytes),
37689 Self::ACTUATOR_OUTPUT_STATUS(body) => body.ser(version, bytes),
37690 Self::ADSB_VEHICLE(body) => body.ser(version, bytes),
37691 Self::AIS_VESSEL(body) => body.ser(version, bytes),
37692 Self::ALTITUDE(body) => body.ser(version, bytes),
37693 Self::ATTITUDE(body) => body.ser(version, bytes),
37694 Self::ATTITUDE_QUATERNION(body) => body.ser(version, bytes),
37695 Self::ATTITUDE_QUATERNION_COV(body) => body.ser(version, bytes),
37696 Self::ATTITUDE_TARGET(body) => body.ser(version, bytes),
37697 Self::ATT_POS_MOCAP(body) => body.ser(version, bytes),
37698 Self::AUTH_KEY(body) => body.ser(version, bytes),
37699 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(body) => body.ser(version, bytes),
37700 Self::AUTOPILOT_VERSION(body) => body.ser(version, bytes),
37701 Self::AVAILABLE_MODES(body) => body.ser(version, bytes),
37702 Self::AVAILABLE_MODES_MONITOR(body) => body.ser(version, bytes),
37703 Self::BATTERY_INFO(body) => body.ser(version, bytes),
37704 Self::BATTERY_STATUS(body) => body.ser(version, bytes),
37705 Self::BUTTON_CHANGE(body) => body.ser(version, bytes),
37706 Self::CAMERA_CAPTURE_STATUS(body) => body.ser(version, bytes),
37707 Self::CAMERA_FOV_STATUS(body) => body.ser(version, bytes),
37708 Self::CAMERA_IMAGE_CAPTURED(body) => body.ser(version, bytes),
37709 Self::CAMERA_INFORMATION(body) => body.ser(version, bytes),
37710 Self::CAMERA_SETTINGS(body) => body.ser(version, bytes),
37711 Self::CAMERA_THERMAL_RANGE(body) => body.ser(version, bytes),
37712 Self::CAMERA_TRACKING_GEO_STATUS(body) => body.ser(version, bytes),
37713 Self::CAMERA_TRACKING_IMAGE_STATUS(body) => body.ser(version, bytes),
37714 Self::CAMERA_TRIGGER(body) => body.ser(version, bytes),
37715 Self::CANFD_FRAME(body) => body.ser(version, bytes),
37716 Self::CAN_FILTER_MODIFY(body) => body.ser(version, bytes),
37717 Self::CAN_FRAME(body) => body.ser(version, bytes),
37718 Self::CELLULAR_CONFIG(body) => body.ser(version, bytes),
37719 Self::CELLULAR_STATUS(body) => body.ser(version, bytes),
37720 Self::CHANGE_OPERATOR_CONTROL(body) => body.ser(version, bytes),
37721 Self::CHANGE_OPERATOR_CONTROL_ACK(body) => body.ser(version, bytes),
37722 Self::COLLISION(body) => body.ser(version, bytes),
37723 Self::COMMAND_ACK(body) => body.ser(version, bytes),
37724 Self::COMMAND_CANCEL(body) => body.ser(version, bytes),
37725 Self::COMMAND_INT(body) => body.ser(version, bytes),
37726 Self::COMMAND_LONG(body) => body.ser(version, bytes),
37727 Self::COMPONENT_INFORMATION(body) => body.ser(version, bytes),
37728 Self::COMPONENT_INFORMATION_BASIC(body) => body.ser(version, bytes),
37729 Self::COMPONENT_METADATA(body) => body.ser(version, bytes),
37730 Self::CONTROL_SYSTEM_STATE(body) => body.ser(version, bytes),
37731 Self::CURRENT_EVENT_SEQUENCE(body) => body.ser(version, bytes),
37732 Self::CURRENT_MODE(body) => body.ser(version, bytes),
37733 Self::DATA_STREAM(body) => body.ser(version, bytes),
37734 Self::DATA_TRANSMISSION_HANDSHAKE(body) => body.ser(version, bytes),
37735 Self::DEBUG(body) => body.ser(version, bytes),
37736 Self::DEBUG_FLOAT_ARRAY(body) => body.ser(version, bytes),
37737 Self::DEBUG_VECT(body) => body.ser(version, bytes),
37738 Self::DISTANCE_SENSOR(body) => body.ser(version, bytes),
37739 Self::EFI_STATUS(body) => body.ser(version, bytes),
37740 Self::ENCAPSULATED_DATA(body) => body.ser(version, bytes),
37741 Self::ESC_INFO(body) => body.ser(version, bytes),
37742 Self::ESC_STATUS(body) => body.ser(version, bytes),
37743 Self::ESTIMATOR_STATUS(body) => body.ser(version, bytes),
37744 Self::EVENT(body) => body.ser(version, bytes),
37745 Self::EXTENDED_SYS_STATE(body) => body.ser(version, bytes),
37746 Self::FENCE_STATUS(body) => body.ser(version, bytes),
37747 Self::FILE_TRANSFER_PROTOCOL(body) => body.ser(version, bytes),
37748 Self::FLIGHT_INFORMATION(body) => body.ser(version, bytes),
37749 Self::FOLLOW_TARGET(body) => body.ser(version, bytes),
37750 Self::FUEL_STATUS(body) => body.ser(version, bytes),
37751 Self::GENERATOR_STATUS(body) => body.ser(version, bytes),
37752 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(body) => body.ser(version, bytes),
37753 Self::GIMBAL_DEVICE_INFORMATION(body) => body.ser(version, bytes),
37754 Self::GIMBAL_DEVICE_SET_ATTITUDE(body) => body.ser(version, bytes),
37755 Self::GIMBAL_MANAGER_INFORMATION(body) => body.ser(version, bytes),
37756 Self::GIMBAL_MANAGER_SET_ATTITUDE(body) => body.ser(version, bytes),
37757 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(body) => body.ser(version, bytes),
37758 Self::GIMBAL_MANAGER_SET_PITCHYAW(body) => body.ser(version, bytes),
37759 Self::GIMBAL_MANAGER_STATUS(body) => body.ser(version, bytes),
37760 Self::GLOBAL_POSITION_INT(body) => body.ser(version, bytes),
37761 Self::GLOBAL_POSITION_INT_COV(body) => body.ser(version, bytes),
37762 Self::GLOBAL_VISION_POSITION_ESTIMATE(body) => body.ser(version, bytes),
37763 Self::GPS2_RAW(body) => body.ser(version, bytes),
37764 Self::GPS2_RTK(body) => body.ser(version, bytes),
37765 Self::GPS_GLOBAL_ORIGIN(body) => body.ser(version, bytes),
37766 Self::GPS_INJECT_DATA(body) => body.ser(version, bytes),
37767 Self::GPS_INPUT(body) => body.ser(version, bytes),
37768 Self::GPS_RAW_INT(body) => body.ser(version, bytes),
37769 Self::GPS_RTCM_DATA(body) => body.ser(version, bytes),
37770 Self::GPS_RTK(body) => body.ser(version, bytes),
37771 Self::GPS_STATUS(body) => body.ser(version, bytes),
37772 Self::HEARTBEAT(body) => body.ser(version, bytes),
37773 Self::HIGHRES_IMU(body) => body.ser(version, bytes),
37774 Self::HIGH_LATENCY(body) => body.ser(version, bytes),
37775 Self::HIGH_LATENCY2(body) => body.ser(version, bytes),
37776 Self::HIL_ACTUATOR_CONTROLS(body) => body.ser(version, bytes),
37777 Self::HIL_CONTROLS(body) => body.ser(version, bytes),
37778 Self::HIL_GPS(body) => body.ser(version, bytes),
37779 Self::HIL_OPTICAL_FLOW(body) => body.ser(version, bytes),
37780 Self::HIL_RC_INPUTS_RAW(body) => body.ser(version, bytes),
37781 Self::HIL_SENSOR(body) => body.ser(version, bytes),
37782 Self::HIL_STATE(body) => body.ser(version, bytes),
37783 Self::HIL_STATE_QUATERNION(body) => body.ser(version, bytes),
37784 Self::HOME_POSITION(body) => body.ser(version, bytes),
37785 Self::HYGROMETER_SENSOR(body) => body.ser(version, bytes),
37786 Self::ILLUMINATOR_STATUS(body) => body.ser(version, bytes),
37787 Self::ISBD_LINK_STATUS(body) => body.ser(version, bytes),
37788 Self::LANDING_TARGET(body) => body.ser(version, bytes),
37789 Self::LINK_NODE_STATUS(body) => body.ser(version, bytes),
37790 Self::LOCAL_POSITION_NED(body) => body.ser(version, bytes),
37791 Self::LOCAL_POSITION_NED_COV(body) => body.ser(version, bytes),
37792 Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(body) => body.ser(version, bytes),
37793 Self::LOGGING_ACK(body) => body.ser(version, bytes),
37794 Self::LOGGING_DATA(body) => body.ser(version, bytes),
37795 Self::LOGGING_DATA_ACKED(body) => body.ser(version, bytes),
37796 Self::LOG_DATA(body) => body.ser(version, bytes),
37797 Self::LOG_ENTRY(body) => body.ser(version, bytes),
37798 Self::LOG_ERASE(body) => body.ser(version, bytes),
37799 Self::LOG_REQUEST_DATA(body) => body.ser(version, bytes),
37800 Self::LOG_REQUEST_END(body) => body.ser(version, bytes),
37801 Self::LOG_REQUEST_LIST(body) => body.ser(version, bytes),
37802 Self::MAG_CAL_REPORT(body) => body.ser(version, bytes),
37803 Self::MANUAL_CONTROL(body) => body.ser(version, bytes),
37804 Self::MANUAL_SETPOINT(body) => body.ser(version, bytes),
37805 Self::MEMORY_VECT(body) => body.ser(version, bytes),
37806 Self::MESSAGE_INTERVAL(body) => body.ser(version, bytes),
37807 Self::MISSION_ACK(body) => body.ser(version, bytes),
37808 Self::MISSION_CLEAR_ALL(body) => body.ser(version, bytes),
37809 Self::MISSION_COUNT(body) => body.ser(version, bytes),
37810 Self::MISSION_CURRENT(body) => body.ser(version, bytes),
37811 Self::MISSION_ITEM(body) => body.ser(version, bytes),
37812 Self::MISSION_ITEM_INT(body) => body.ser(version, bytes),
37813 Self::MISSION_ITEM_REACHED(body) => body.ser(version, bytes),
37814 Self::MISSION_REQUEST(body) => body.ser(version, bytes),
37815 Self::MISSION_REQUEST_INT(body) => body.ser(version, bytes),
37816 Self::MISSION_REQUEST_LIST(body) => body.ser(version, bytes),
37817 Self::MISSION_REQUEST_PARTIAL_LIST(body) => body.ser(version, bytes),
37818 Self::MISSION_SET_CURRENT(body) => body.ser(version, bytes),
37819 Self::MISSION_WRITE_PARTIAL_LIST(body) => body.ser(version, bytes),
37820 Self::MOUNT_ORIENTATION(body) => body.ser(version, bytes),
37821 Self::NAMED_VALUE_FLOAT(body) => body.ser(version, bytes),
37822 Self::NAMED_VALUE_INT(body) => body.ser(version, bytes),
37823 Self::NAV_CONTROLLER_OUTPUT(body) => body.ser(version, bytes),
37824 Self::OBSTACLE_DISTANCE(body) => body.ser(version, bytes),
37825 Self::ODOMETRY(body) => body.ser(version, bytes),
37826 Self::ONBOARD_COMPUTER_STATUS(body) => body.ser(version, bytes),
37827 Self::OPEN_DRONE_ID_ARM_STATUS(body) => body.ser(version, bytes),
37828 Self::OPEN_DRONE_ID_AUTHENTICATION(body) => body.ser(version, bytes),
37829 Self::OPEN_DRONE_ID_BASIC_ID(body) => body.ser(version, bytes),
37830 Self::OPEN_DRONE_ID_LOCATION(body) => body.ser(version, bytes),
37831 Self::OPEN_DRONE_ID_MESSAGE_PACK(body) => body.ser(version, bytes),
37832 Self::OPEN_DRONE_ID_OPERATOR_ID(body) => body.ser(version, bytes),
37833 Self::OPEN_DRONE_ID_SELF_ID(body) => body.ser(version, bytes),
37834 Self::OPEN_DRONE_ID_SYSTEM(body) => body.ser(version, bytes),
37835 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(body) => body.ser(version, bytes),
37836 Self::OPTICAL_FLOW(body) => body.ser(version, bytes),
37837 Self::OPTICAL_FLOW_RAD(body) => body.ser(version, bytes),
37838 Self::ORBIT_EXECUTION_STATUS(body) => body.ser(version, bytes),
37839 Self::PARAM_EXT_ACK(body) => body.ser(version, bytes),
37840 Self::PARAM_EXT_REQUEST_LIST(body) => body.ser(version, bytes),
37841 Self::PARAM_EXT_REQUEST_READ(body) => body.ser(version, bytes),
37842 Self::PARAM_EXT_SET(body) => body.ser(version, bytes),
37843 Self::PARAM_EXT_VALUE(body) => body.ser(version, bytes),
37844 Self::PARAM_MAP_RC(body) => body.ser(version, bytes),
37845 Self::PARAM_REQUEST_LIST(body) => body.ser(version, bytes),
37846 Self::PARAM_REQUEST_READ(body) => body.ser(version, bytes),
37847 Self::PARAM_SET(body) => body.ser(version, bytes),
37848 Self::PARAM_VALUE(body) => body.ser(version, bytes),
37849 Self::PING(body) => body.ser(version, bytes),
37850 Self::PLAY_TUNE(body) => body.ser(version, bytes),
37851 Self::PLAY_TUNE_V2(body) => body.ser(version, bytes),
37852 Self::POSITION_TARGET_GLOBAL_INT(body) => body.ser(version, bytes),
37853 Self::POSITION_TARGET_LOCAL_NED(body) => body.ser(version, bytes),
37854 Self::POWER_STATUS(body) => body.ser(version, bytes),
37855 Self::PROTOCOL_VERSION(body) => body.ser(version, bytes),
37856 Self::RADIO_STATUS(body) => body.ser(version, bytes),
37857 Self::RAW_IMU(body) => body.ser(version, bytes),
37858 Self::RAW_PRESSURE(body) => body.ser(version, bytes),
37859 Self::RAW_RPM(body) => body.ser(version, bytes),
37860 Self::RC_CHANNELS(body) => body.ser(version, bytes),
37861 Self::RC_CHANNELS_OVERRIDE(body) => body.ser(version, bytes),
37862 Self::RC_CHANNELS_RAW(body) => body.ser(version, bytes),
37863 Self::RC_CHANNELS_SCALED(body) => body.ser(version, bytes),
37864 Self::REQUEST_DATA_STREAM(body) => body.ser(version, bytes),
37865 Self::REQUEST_EVENT(body) => body.ser(version, bytes),
37866 Self::RESOURCE_REQUEST(body) => body.ser(version, bytes),
37867 Self::RESPONSE_EVENT_ERROR(body) => body.ser(version, bytes),
37868 Self::SAFETY_ALLOWED_AREA(body) => body.ser(version, bytes),
37869 Self::SAFETY_SET_ALLOWED_AREA(body) => body.ser(version, bytes),
37870 Self::SCALED_IMU(body) => body.ser(version, bytes),
37871 Self::SCALED_IMU2(body) => body.ser(version, bytes),
37872 Self::SCALED_IMU3(body) => body.ser(version, bytes),
37873 Self::SCALED_PRESSURE(body) => body.ser(version, bytes),
37874 Self::SCALED_PRESSURE2(body) => body.ser(version, bytes),
37875 Self::SCALED_PRESSURE3(body) => body.ser(version, bytes),
37876 Self::SERIAL_CONTROL(body) => body.ser(version, bytes),
37877 Self::SERVO_OUTPUT_RAW(body) => body.ser(version, bytes),
37878 Self::SETUP_SIGNING(body) => body.ser(version, bytes),
37879 Self::SET_ACTUATOR_CONTROL_TARGET(body) => body.ser(version, bytes),
37880 Self::SET_ATTITUDE_TARGET(body) => body.ser(version, bytes),
37881 Self::SET_GPS_GLOBAL_ORIGIN(body) => body.ser(version, bytes),
37882 Self::SET_HOME_POSITION(body) => body.ser(version, bytes),
37883 Self::SET_MODE(body) => body.ser(version, bytes),
37884 Self::SET_POSITION_TARGET_GLOBAL_INT(body) => body.ser(version, bytes),
37885 Self::SET_POSITION_TARGET_LOCAL_NED(body) => body.ser(version, bytes),
37886 Self::SIM_STATE(body) => body.ser(version, bytes),
37887 Self::SMART_BATTERY_INFO(body) => body.ser(version, bytes),
37888 Self::STATUSTEXT(body) => body.ser(version, bytes),
37889 Self::STORAGE_INFORMATION(body) => body.ser(version, bytes),
37890 Self::SUPPORTED_TUNES(body) => body.ser(version, bytes),
37891 Self::SYSTEM_TIME(body) => body.ser(version, bytes),
37892 Self::SYS_STATUS(body) => body.ser(version, bytes),
37893 Self::TERRAIN_CHECK(body) => body.ser(version, bytes),
37894 Self::TERRAIN_DATA(body) => body.ser(version, bytes),
37895 Self::TERRAIN_REPORT(body) => body.ser(version, bytes),
37896 Self::TERRAIN_REQUEST(body) => body.ser(version, bytes),
37897 Self::TIMESYNC(body) => body.ser(version, bytes),
37898 Self::TIME_ESTIMATE_TO_TARGET(body) => body.ser(version, bytes),
37899 Self::TRAJECTORY_REPRESENTATION_BEZIER(body) => body.ser(version, bytes),
37900 Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(body) => body.ser(version, bytes),
37901 Self::TUNNEL(body) => body.ser(version, bytes),
37902 Self::UAVCAN_NODE_INFO(body) => body.ser(version, bytes),
37903 Self::UAVCAN_NODE_STATUS(body) => body.ser(version, bytes),
37904 Self::UTM_GLOBAL_POSITION(body) => body.ser(version, bytes),
37905 Self::V2_EXTENSION(body) => body.ser(version, bytes),
37906 Self::VFR_HUD(body) => body.ser(version, bytes),
37907 Self::VIBRATION(body) => body.ser(version, bytes),
37908 Self::VICON_POSITION_ESTIMATE(body) => body.ser(version, bytes),
37909 Self::VIDEO_STREAM_INFORMATION(body) => body.ser(version, bytes),
37910 Self::VIDEO_STREAM_STATUS(body) => body.ser(version, bytes),
37911 Self::VISION_POSITION_ESTIMATE(body) => body.ser(version, bytes),
37912 Self::VISION_SPEED_ESTIMATE(body) => body.ser(version, bytes),
37913 Self::WHEEL_DISTANCE(body) => body.ser(version, bytes),
37914 Self::WIFI_CONFIG_AP(body) => body.ser(version, bytes),
37915 Self::WINCH_STATUS(body) => body.ser(version, bytes),
37916 Self::WIND_COV(body) => body.ser(version, bytes),
37917 }
37918 }
37919 fn extra_crc(id: u32) -> u8 {
37920 match id {
37921 ACTUATOR_CONTROL_TARGET_DATA::ID => ACTUATOR_CONTROL_TARGET_DATA::EXTRA_CRC,
37922 ACTUATOR_OUTPUT_STATUS_DATA::ID => ACTUATOR_OUTPUT_STATUS_DATA::EXTRA_CRC,
37923 ADSB_VEHICLE_DATA::ID => ADSB_VEHICLE_DATA::EXTRA_CRC,
37924 AIS_VESSEL_DATA::ID => AIS_VESSEL_DATA::EXTRA_CRC,
37925 ALTITUDE_DATA::ID => ALTITUDE_DATA::EXTRA_CRC,
37926 ATTITUDE_DATA::ID => ATTITUDE_DATA::EXTRA_CRC,
37927 ATTITUDE_QUATERNION_DATA::ID => ATTITUDE_QUATERNION_DATA::EXTRA_CRC,
37928 ATTITUDE_QUATERNION_COV_DATA::ID => ATTITUDE_QUATERNION_COV_DATA::EXTRA_CRC,
37929 ATTITUDE_TARGET_DATA::ID => ATTITUDE_TARGET_DATA::EXTRA_CRC,
37930 ATT_POS_MOCAP_DATA::ID => ATT_POS_MOCAP_DATA::EXTRA_CRC,
37931 AUTH_KEY_DATA::ID => AUTH_KEY_DATA::EXTRA_CRC,
37932 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID => {
37933 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::EXTRA_CRC
37934 }
37935 AUTOPILOT_VERSION_DATA::ID => AUTOPILOT_VERSION_DATA::EXTRA_CRC,
37936 AVAILABLE_MODES_DATA::ID => AVAILABLE_MODES_DATA::EXTRA_CRC,
37937 AVAILABLE_MODES_MONITOR_DATA::ID => AVAILABLE_MODES_MONITOR_DATA::EXTRA_CRC,
37938 BATTERY_INFO_DATA::ID => BATTERY_INFO_DATA::EXTRA_CRC,
37939 BATTERY_STATUS_DATA::ID => BATTERY_STATUS_DATA::EXTRA_CRC,
37940 BUTTON_CHANGE_DATA::ID => BUTTON_CHANGE_DATA::EXTRA_CRC,
37941 CAMERA_CAPTURE_STATUS_DATA::ID => CAMERA_CAPTURE_STATUS_DATA::EXTRA_CRC,
37942 CAMERA_FOV_STATUS_DATA::ID => CAMERA_FOV_STATUS_DATA::EXTRA_CRC,
37943 CAMERA_IMAGE_CAPTURED_DATA::ID => CAMERA_IMAGE_CAPTURED_DATA::EXTRA_CRC,
37944 CAMERA_INFORMATION_DATA::ID => CAMERA_INFORMATION_DATA::EXTRA_CRC,
37945 CAMERA_SETTINGS_DATA::ID => CAMERA_SETTINGS_DATA::EXTRA_CRC,
37946 CAMERA_THERMAL_RANGE_DATA::ID => CAMERA_THERMAL_RANGE_DATA::EXTRA_CRC,
37947 CAMERA_TRACKING_GEO_STATUS_DATA::ID => CAMERA_TRACKING_GEO_STATUS_DATA::EXTRA_CRC,
37948 CAMERA_TRACKING_IMAGE_STATUS_DATA::ID => CAMERA_TRACKING_IMAGE_STATUS_DATA::EXTRA_CRC,
37949 CAMERA_TRIGGER_DATA::ID => CAMERA_TRIGGER_DATA::EXTRA_CRC,
37950 CANFD_FRAME_DATA::ID => CANFD_FRAME_DATA::EXTRA_CRC,
37951 CAN_FILTER_MODIFY_DATA::ID => CAN_FILTER_MODIFY_DATA::EXTRA_CRC,
37952 CAN_FRAME_DATA::ID => CAN_FRAME_DATA::EXTRA_CRC,
37953 CELLULAR_CONFIG_DATA::ID => CELLULAR_CONFIG_DATA::EXTRA_CRC,
37954 CELLULAR_STATUS_DATA::ID => CELLULAR_STATUS_DATA::EXTRA_CRC,
37955 CHANGE_OPERATOR_CONTROL_DATA::ID => CHANGE_OPERATOR_CONTROL_DATA::EXTRA_CRC,
37956 CHANGE_OPERATOR_CONTROL_ACK_DATA::ID => CHANGE_OPERATOR_CONTROL_ACK_DATA::EXTRA_CRC,
37957 COLLISION_DATA::ID => COLLISION_DATA::EXTRA_CRC,
37958 COMMAND_ACK_DATA::ID => COMMAND_ACK_DATA::EXTRA_CRC,
37959 COMMAND_CANCEL_DATA::ID => COMMAND_CANCEL_DATA::EXTRA_CRC,
37960 COMMAND_INT_DATA::ID => COMMAND_INT_DATA::EXTRA_CRC,
37961 COMMAND_LONG_DATA::ID => COMMAND_LONG_DATA::EXTRA_CRC,
37962 COMPONENT_INFORMATION_DATA::ID => COMPONENT_INFORMATION_DATA::EXTRA_CRC,
37963 COMPONENT_INFORMATION_BASIC_DATA::ID => COMPONENT_INFORMATION_BASIC_DATA::EXTRA_CRC,
37964 COMPONENT_METADATA_DATA::ID => COMPONENT_METADATA_DATA::EXTRA_CRC,
37965 CONTROL_SYSTEM_STATE_DATA::ID => CONTROL_SYSTEM_STATE_DATA::EXTRA_CRC,
37966 CURRENT_EVENT_SEQUENCE_DATA::ID => CURRENT_EVENT_SEQUENCE_DATA::EXTRA_CRC,
37967 CURRENT_MODE_DATA::ID => CURRENT_MODE_DATA::EXTRA_CRC,
37968 DATA_STREAM_DATA::ID => DATA_STREAM_DATA::EXTRA_CRC,
37969 DATA_TRANSMISSION_HANDSHAKE_DATA::ID => DATA_TRANSMISSION_HANDSHAKE_DATA::EXTRA_CRC,
37970 DEBUG_DATA::ID => DEBUG_DATA::EXTRA_CRC,
37971 DEBUG_FLOAT_ARRAY_DATA::ID => DEBUG_FLOAT_ARRAY_DATA::EXTRA_CRC,
37972 DEBUG_VECT_DATA::ID => DEBUG_VECT_DATA::EXTRA_CRC,
37973 DISTANCE_SENSOR_DATA::ID => DISTANCE_SENSOR_DATA::EXTRA_CRC,
37974 EFI_STATUS_DATA::ID => EFI_STATUS_DATA::EXTRA_CRC,
37975 ENCAPSULATED_DATA_DATA::ID => ENCAPSULATED_DATA_DATA::EXTRA_CRC,
37976 ESC_INFO_DATA::ID => ESC_INFO_DATA::EXTRA_CRC,
37977 ESC_STATUS_DATA::ID => ESC_STATUS_DATA::EXTRA_CRC,
37978 ESTIMATOR_STATUS_DATA::ID => ESTIMATOR_STATUS_DATA::EXTRA_CRC,
37979 EVENT_DATA::ID => EVENT_DATA::EXTRA_CRC,
37980 EXTENDED_SYS_STATE_DATA::ID => EXTENDED_SYS_STATE_DATA::EXTRA_CRC,
37981 FENCE_STATUS_DATA::ID => FENCE_STATUS_DATA::EXTRA_CRC,
37982 FILE_TRANSFER_PROTOCOL_DATA::ID => FILE_TRANSFER_PROTOCOL_DATA::EXTRA_CRC,
37983 FLIGHT_INFORMATION_DATA::ID => FLIGHT_INFORMATION_DATA::EXTRA_CRC,
37984 FOLLOW_TARGET_DATA::ID => FOLLOW_TARGET_DATA::EXTRA_CRC,
37985 FUEL_STATUS_DATA::ID => FUEL_STATUS_DATA::EXTRA_CRC,
37986 GENERATOR_STATUS_DATA::ID => GENERATOR_STATUS_DATA::EXTRA_CRC,
37987 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID => GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::EXTRA_CRC,
37988 GIMBAL_DEVICE_INFORMATION_DATA::ID => GIMBAL_DEVICE_INFORMATION_DATA::EXTRA_CRC,
37989 GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID => GIMBAL_DEVICE_SET_ATTITUDE_DATA::EXTRA_CRC,
37990 GIMBAL_MANAGER_INFORMATION_DATA::ID => GIMBAL_MANAGER_INFORMATION_DATA::EXTRA_CRC,
37991 GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID => GIMBAL_MANAGER_SET_ATTITUDE_DATA::EXTRA_CRC,
37992 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID => {
37993 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::EXTRA_CRC
37994 }
37995 GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID => GIMBAL_MANAGER_SET_PITCHYAW_DATA::EXTRA_CRC,
37996 GIMBAL_MANAGER_STATUS_DATA::ID => GIMBAL_MANAGER_STATUS_DATA::EXTRA_CRC,
37997 GLOBAL_POSITION_INT_DATA::ID => GLOBAL_POSITION_INT_DATA::EXTRA_CRC,
37998 GLOBAL_POSITION_INT_COV_DATA::ID => GLOBAL_POSITION_INT_COV_DATA::EXTRA_CRC,
37999 GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID => {
38000 GLOBAL_VISION_POSITION_ESTIMATE_DATA::EXTRA_CRC
38001 }
38002 GPS2_RAW_DATA::ID => GPS2_RAW_DATA::EXTRA_CRC,
38003 GPS2_RTK_DATA::ID => GPS2_RTK_DATA::EXTRA_CRC,
38004 GPS_GLOBAL_ORIGIN_DATA::ID => GPS_GLOBAL_ORIGIN_DATA::EXTRA_CRC,
38005 GPS_INJECT_DATA_DATA::ID => GPS_INJECT_DATA_DATA::EXTRA_CRC,
38006 GPS_INPUT_DATA::ID => GPS_INPUT_DATA::EXTRA_CRC,
38007 GPS_RAW_INT_DATA::ID => GPS_RAW_INT_DATA::EXTRA_CRC,
38008 GPS_RTCM_DATA_DATA::ID => GPS_RTCM_DATA_DATA::EXTRA_CRC,
38009 GPS_RTK_DATA::ID => GPS_RTK_DATA::EXTRA_CRC,
38010 GPS_STATUS_DATA::ID => GPS_STATUS_DATA::EXTRA_CRC,
38011 HEARTBEAT_DATA::ID => HEARTBEAT_DATA::EXTRA_CRC,
38012 HIGHRES_IMU_DATA::ID => HIGHRES_IMU_DATA::EXTRA_CRC,
38013 HIGH_LATENCY_DATA::ID => HIGH_LATENCY_DATA::EXTRA_CRC,
38014 HIGH_LATENCY2_DATA::ID => HIGH_LATENCY2_DATA::EXTRA_CRC,
38015 HIL_ACTUATOR_CONTROLS_DATA::ID => HIL_ACTUATOR_CONTROLS_DATA::EXTRA_CRC,
38016 HIL_CONTROLS_DATA::ID => HIL_CONTROLS_DATA::EXTRA_CRC,
38017 HIL_GPS_DATA::ID => HIL_GPS_DATA::EXTRA_CRC,
38018 HIL_OPTICAL_FLOW_DATA::ID => HIL_OPTICAL_FLOW_DATA::EXTRA_CRC,
38019 HIL_RC_INPUTS_RAW_DATA::ID => HIL_RC_INPUTS_RAW_DATA::EXTRA_CRC,
38020 HIL_SENSOR_DATA::ID => HIL_SENSOR_DATA::EXTRA_CRC,
38021 HIL_STATE_DATA::ID => HIL_STATE_DATA::EXTRA_CRC,
38022 HIL_STATE_QUATERNION_DATA::ID => HIL_STATE_QUATERNION_DATA::EXTRA_CRC,
38023 HOME_POSITION_DATA::ID => HOME_POSITION_DATA::EXTRA_CRC,
38024 HYGROMETER_SENSOR_DATA::ID => HYGROMETER_SENSOR_DATA::EXTRA_CRC,
38025 ILLUMINATOR_STATUS_DATA::ID => ILLUMINATOR_STATUS_DATA::EXTRA_CRC,
38026 ISBD_LINK_STATUS_DATA::ID => ISBD_LINK_STATUS_DATA::EXTRA_CRC,
38027 LANDING_TARGET_DATA::ID => LANDING_TARGET_DATA::EXTRA_CRC,
38028 LINK_NODE_STATUS_DATA::ID => LINK_NODE_STATUS_DATA::EXTRA_CRC,
38029 LOCAL_POSITION_NED_DATA::ID => LOCAL_POSITION_NED_DATA::EXTRA_CRC,
38030 LOCAL_POSITION_NED_COV_DATA::ID => LOCAL_POSITION_NED_COV_DATA::EXTRA_CRC,
38031 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID => {
38032 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::EXTRA_CRC
38033 }
38034 LOGGING_ACK_DATA::ID => LOGGING_ACK_DATA::EXTRA_CRC,
38035 LOGGING_DATA_DATA::ID => LOGGING_DATA_DATA::EXTRA_CRC,
38036 LOGGING_DATA_ACKED_DATA::ID => LOGGING_DATA_ACKED_DATA::EXTRA_CRC,
38037 LOG_DATA_DATA::ID => LOG_DATA_DATA::EXTRA_CRC,
38038 LOG_ENTRY_DATA::ID => LOG_ENTRY_DATA::EXTRA_CRC,
38039 LOG_ERASE_DATA::ID => LOG_ERASE_DATA::EXTRA_CRC,
38040 LOG_REQUEST_DATA_DATA::ID => LOG_REQUEST_DATA_DATA::EXTRA_CRC,
38041 LOG_REQUEST_END_DATA::ID => LOG_REQUEST_END_DATA::EXTRA_CRC,
38042 LOG_REQUEST_LIST_DATA::ID => LOG_REQUEST_LIST_DATA::EXTRA_CRC,
38043 MAG_CAL_REPORT_DATA::ID => MAG_CAL_REPORT_DATA::EXTRA_CRC,
38044 MANUAL_CONTROL_DATA::ID => MANUAL_CONTROL_DATA::EXTRA_CRC,
38045 MANUAL_SETPOINT_DATA::ID => MANUAL_SETPOINT_DATA::EXTRA_CRC,
38046 MEMORY_VECT_DATA::ID => MEMORY_VECT_DATA::EXTRA_CRC,
38047 MESSAGE_INTERVAL_DATA::ID => MESSAGE_INTERVAL_DATA::EXTRA_CRC,
38048 MISSION_ACK_DATA::ID => MISSION_ACK_DATA::EXTRA_CRC,
38049 MISSION_CLEAR_ALL_DATA::ID => MISSION_CLEAR_ALL_DATA::EXTRA_CRC,
38050 MISSION_COUNT_DATA::ID => MISSION_COUNT_DATA::EXTRA_CRC,
38051 MISSION_CURRENT_DATA::ID => MISSION_CURRENT_DATA::EXTRA_CRC,
38052 MISSION_ITEM_DATA::ID => MISSION_ITEM_DATA::EXTRA_CRC,
38053 MISSION_ITEM_INT_DATA::ID => MISSION_ITEM_INT_DATA::EXTRA_CRC,
38054 MISSION_ITEM_REACHED_DATA::ID => MISSION_ITEM_REACHED_DATA::EXTRA_CRC,
38055 MISSION_REQUEST_DATA::ID => MISSION_REQUEST_DATA::EXTRA_CRC,
38056 MISSION_REQUEST_INT_DATA::ID => MISSION_REQUEST_INT_DATA::EXTRA_CRC,
38057 MISSION_REQUEST_LIST_DATA::ID => MISSION_REQUEST_LIST_DATA::EXTRA_CRC,
38058 MISSION_REQUEST_PARTIAL_LIST_DATA::ID => MISSION_REQUEST_PARTIAL_LIST_DATA::EXTRA_CRC,
38059 MISSION_SET_CURRENT_DATA::ID => MISSION_SET_CURRENT_DATA::EXTRA_CRC,
38060 MISSION_WRITE_PARTIAL_LIST_DATA::ID => MISSION_WRITE_PARTIAL_LIST_DATA::EXTRA_CRC,
38061 MOUNT_ORIENTATION_DATA::ID => MOUNT_ORIENTATION_DATA::EXTRA_CRC,
38062 NAMED_VALUE_FLOAT_DATA::ID => NAMED_VALUE_FLOAT_DATA::EXTRA_CRC,
38063 NAMED_VALUE_INT_DATA::ID => NAMED_VALUE_INT_DATA::EXTRA_CRC,
38064 NAV_CONTROLLER_OUTPUT_DATA::ID => NAV_CONTROLLER_OUTPUT_DATA::EXTRA_CRC,
38065 OBSTACLE_DISTANCE_DATA::ID => OBSTACLE_DISTANCE_DATA::EXTRA_CRC,
38066 ODOMETRY_DATA::ID => ODOMETRY_DATA::EXTRA_CRC,
38067 ONBOARD_COMPUTER_STATUS_DATA::ID => ONBOARD_COMPUTER_STATUS_DATA::EXTRA_CRC,
38068 OPEN_DRONE_ID_ARM_STATUS_DATA::ID => OPEN_DRONE_ID_ARM_STATUS_DATA::EXTRA_CRC,
38069 OPEN_DRONE_ID_AUTHENTICATION_DATA::ID => OPEN_DRONE_ID_AUTHENTICATION_DATA::EXTRA_CRC,
38070 OPEN_DRONE_ID_BASIC_ID_DATA::ID => OPEN_DRONE_ID_BASIC_ID_DATA::EXTRA_CRC,
38071 OPEN_DRONE_ID_LOCATION_DATA::ID => OPEN_DRONE_ID_LOCATION_DATA::EXTRA_CRC,
38072 OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID => OPEN_DRONE_ID_MESSAGE_PACK_DATA::EXTRA_CRC,
38073 OPEN_DRONE_ID_OPERATOR_ID_DATA::ID => OPEN_DRONE_ID_OPERATOR_ID_DATA::EXTRA_CRC,
38074 OPEN_DRONE_ID_SELF_ID_DATA::ID => OPEN_DRONE_ID_SELF_ID_DATA::EXTRA_CRC,
38075 OPEN_DRONE_ID_SYSTEM_DATA::ID => OPEN_DRONE_ID_SYSTEM_DATA::EXTRA_CRC,
38076 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID => OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::EXTRA_CRC,
38077 OPTICAL_FLOW_DATA::ID => OPTICAL_FLOW_DATA::EXTRA_CRC,
38078 OPTICAL_FLOW_RAD_DATA::ID => OPTICAL_FLOW_RAD_DATA::EXTRA_CRC,
38079 ORBIT_EXECUTION_STATUS_DATA::ID => ORBIT_EXECUTION_STATUS_DATA::EXTRA_CRC,
38080 PARAM_EXT_ACK_DATA::ID => PARAM_EXT_ACK_DATA::EXTRA_CRC,
38081 PARAM_EXT_REQUEST_LIST_DATA::ID => PARAM_EXT_REQUEST_LIST_DATA::EXTRA_CRC,
38082 PARAM_EXT_REQUEST_READ_DATA::ID => PARAM_EXT_REQUEST_READ_DATA::EXTRA_CRC,
38083 PARAM_EXT_SET_DATA::ID => PARAM_EXT_SET_DATA::EXTRA_CRC,
38084 PARAM_EXT_VALUE_DATA::ID => PARAM_EXT_VALUE_DATA::EXTRA_CRC,
38085 PARAM_MAP_RC_DATA::ID => PARAM_MAP_RC_DATA::EXTRA_CRC,
38086 PARAM_REQUEST_LIST_DATA::ID => PARAM_REQUEST_LIST_DATA::EXTRA_CRC,
38087 PARAM_REQUEST_READ_DATA::ID => PARAM_REQUEST_READ_DATA::EXTRA_CRC,
38088 PARAM_SET_DATA::ID => PARAM_SET_DATA::EXTRA_CRC,
38089 PARAM_VALUE_DATA::ID => PARAM_VALUE_DATA::EXTRA_CRC,
38090 PING_DATA::ID => PING_DATA::EXTRA_CRC,
38091 PLAY_TUNE_DATA::ID => PLAY_TUNE_DATA::EXTRA_CRC,
38092 PLAY_TUNE_V2_DATA::ID => PLAY_TUNE_V2_DATA::EXTRA_CRC,
38093 POSITION_TARGET_GLOBAL_INT_DATA::ID => POSITION_TARGET_GLOBAL_INT_DATA::EXTRA_CRC,
38094 POSITION_TARGET_LOCAL_NED_DATA::ID => POSITION_TARGET_LOCAL_NED_DATA::EXTRA_CRC,
38095 POWER_STATUS_DATA::ID => POWER_STATUS_DATA::EXTRA_CRC,
38096 PROTOCOL_VERSION_DATA::ID => PROTOCOL_VERSION_DATA::EXTRA_CRC,
38097 RADIO_STATUS_DATA::ID => RADIO_STATUS_DATA::EXTRA_CRC,
38098 RAW_IMU_DATA::ID => RAW_IMU_DATA::EXTRA_CRC,
38099 RAW_PRESSURE_DATA::ID => RAW_PRESSURE_DATA::EXTRA_CRC,
38100 RAW_RPM_DATA::ID => RAW_RPM_DATA::EXTRA_CRC,
38101 RC_CHANNELS_DATA::ID => RC_CHANNELS_DATA::EXTRA_CRC,
38102 RC_CHANNELS_OVERRIDE_DATA::ID => RC_CHANNELS_OVERRIDE_DATA::EXTRA_CRC,
38103 RC_CHANNELS_RAW_DATA::ID => RC_CHANNELS_RAW_DATA::EXTRA_CRC,
38104 RC_CHANNELS_SCALED_DATA::ID => RC_CHANNELS_SCALED_DATA::EXTRA_CRC,
38105 REQUEST_DATA_STREAM_DATA::ID => REQUEST_DATA_STREAM_DATA::EXTRA_CRC,
38106 REQUEST_EVENT_DATA::ID => REQUEST_EVENT_DATA::EXTRA_CRC,
38107 RESOURCE_REQUEST_DATA::ID => RESOURCE_REQUEST_DATA::EXTRA_CRC,
38108 RESPONSE_EVENT_ERROR_DATA::ID => RESPONSE_EVENT_ERROR_DATA::EXTRA_CRC,
38109 SAFETY_ALLOWED_AREA_DATA::ID => SAFETY_ALLOWED_AREA_DATA::EXTRA_CRC,
38110 SAFETY_SET_ALLOWED_AREA_DATA::ID => SAFETY_SET_ALLOWED_AREA_DATA::EXTRA_CRC,
38111 SCALED_IMU_DATA::ID => SCALED_IMU_DATA::EXTRA_CRC,
38112 SCALED_IMU2_DATA::ID => SCALED_IMU2_DATA::EXTRA_CRC,
38113 SCALED_IMU3_DATA::ID => SCALED_IMU3_DATA::EXTRA_CRC,
38114 SCALED_PRESSURE_DATA::ID => SCALED_PRESSURE_DATA::EXTRA_CRC,
38115 SCALED_PRESSURE2_DATA::ID => SCALED_PRESSURE2_DATA::EXTRA_CRC,
38116 SCALED_PRESSURE3_DATA::ID => SCALED_PRESSURE3_DATA::EXTRA_CRC,
38117 SERIAL_CONTROL_DATA::ID => SERIAL_CONTROL_DATA::EXTRA_CRC,
38118 SERVO_OUTPUT_RAW_DATA::ID => SERVO_OUTPUT_RAW_DATA::EXTRA_CRC,
38119 SETUP_SIGNING_DATA::ID => SETUP_SIGNING_DATA::EXTRA_CRC,
38120 SET_ACTUATOR_CONTROL_TARGET_DATA::ID => SET_ACTUATOR_CONTROL_TARGET_DATA::EXTRA_CRC,
38121 SET_ATTITUDE_TARGET_DATA::ID => SET_ATTITUDE_TARGET_DATA::EXTRA_CRC,
38122 SET_GPS_GLOBAL_ORIGIN_DATA::ID => SET_GPS_GLOBAL_ORIGIN_DATA::EXTRA_CRC,
38123 SET_HOME_POSITION_DATA::ID => SET_HOME_POSITION_DATA::EXTRA_CRC,
38124 SET_MODE_DATA::ID => SET_MODE_DATA::EXTRA_CRC,
38125 SET_POSITION_TARGET_GLOBAL_INT_DATA::ID => {
38126 SET_POSITION_TARGET_GLOBAL_INT_DATA::EXTRA_CRC
38127 }
38128 SET_POSITION_TARGET_LOCAL_NED_DATA::ID => SET_POSITION_TARGET_LOCAL_NED_DATA::EXTRA_CRC,
38129 SIM_STATE_DATA::ID => SIM_STATE_DATA::EXTRA_CRC,
38130 SMART_BATTERY_INFO_DATA::ID => SMART_BATTERY_INFO_DATA::EXTRA_CRC,
38131 STATUSTEXT_DATA::ID => STATUSTEXT_DATA::EXTRA_CRC,
38132 STORAGE_INFORMATION_DATA::ID => STORAGE_INFORMATION_DATA::EXTRA_CRC,
38133 SUPPORTED_TUNES_DATA::ID => SUPPORTED_TUNES_DATA::EXTRA_CRC,
38134 SYSTEM_TIME_DATA::ID => SYSTEM_TIME_DATA::EXTRA_CRC,
38135 SYS_STATUS_DATA::ID => SYS_STATUS_DATA::EXTRA_CRC,
38136 TERRAIN_CHECK_DATA::ID => TERRAIN_CHECK_DATA::EXTRA_CRC,
38137 TERRAIN_DATA_DATA::ID => TERRAIN_DATA_DATA::EXTRA_CRC,
38138 TERRAIN_REPORT_DATA::ID => TERRAIN_REPORT_DATA::EXTRA_CRC,
38139 TERRAIN_REQUEST_DATA::ID => TERRAIN_REQUEST_DATA::EXTRA_CRC,
38140 TIMESYNC_DATA::ID => TIMESYNC_DATA::EXTRA_CRC,
38141 TIME_ESTIMATE_TO_TARGET_DATA::ID => TIME_ESTIMATE_TO_TARGET_DATA::EXTRA_CRC,
38142 TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID => {
38143 TRAJECTORY_REPRESENTATION_BEZIER_DATA::EXTRA_CRC
38144 }
38145 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID => {
38146 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::EXTRA_CRC
38147 }
38148 TUNNEL_DATA::ID => TUNNEL_DATA::EXTRA_CRC,
38149 UAVCAN_NODE_INFO_DATA::ID => UAVCAN_NODE_INFO_DATA::EXTRA_CRC,
38150 UAVCAN_NODE_STATUS_DATA::ID => UAVCAN_NODE_STATUS_DATA::EXTRA_CRC,
38151 UTM_GLOBAL_POSITION_DATA::ID => UTM_GLOBAL_POSITION_DATA::EXTRA_CRC,
38152 V2_EXTENSION_DATA::ID => V2_EXTENSION_DATA::EXTRA_CRC,
38153 VFR_HUD_DATA::ID => VFR_HUD_DATA::EXTRA_CRC,
38154 VIBRATION_DATA::ID => VIBRATION_DATA::EXTRA_CRC,
38155 VICON_POSITION_ESTIMATE_DATA::ID => VICON_POSITION_ESTIMATE_DATA::EXTRA_CRC,
38156 VIDEO_STREAM_INFORMATION_DATA::ID => VIDEO_STREAM_INFORMATION_DATA::EXTRA_CRC,
38157 VIDEO_STREAM_STATUS_DATA::ID => VIDEO_STREAM_STATUS_DATA::EXTRA_CRC,
38158 VISION_POSITION_ESTIMATE_DATA::ID => VISION_POSITION_ESTIMATE_DATA::EXTRA_CRC,
38159 VISION_SPEED_ESTIMATE_DATA::ID => VISION_SPEED_ESTIMATE_DATA::EXTRA_CRC,
38160 WHEEL_DISTANCE_DATA::ID => WHEEL_DISTANCE_DATA::EXTRA_CRC,
38161 WIFI_CONFIG_AP_DATA::ID => WIFI_CONFIG_AP_DATA::EXTRA_CRC,
38162 WINCH_STATUS_DATA::ID => WINCH_STATUS_DATA::EXTRA_CRC,
38163 WIND_COV_DATA::ID => WIND_COV_DATA::EXTRA_CRC,
38164 _ => 0,
38165 }
38166 }
38167 fn target_system_id(&self) -> Option<u8> {
38168 match self {
38169 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(inner) => Some(inner.target_system),
38170 Self::CANFD_FRAME(inner) => Some(inner.target_system),
38171 Self::CAN_FILTER_MODIFY(inner) => Some(inner.target_system),
38172 Self::CAN_FRAME(inner) => Some(inner.target_system),
38173 Self::CHANGE_OPERATOR_CONTROL(inner) => Some(inner.target_system),
38174 Self::COMMAND_ACK(inner) => Some(inner.target_system),
38175 Self::COMMAND_CANCEL(inner) => Some(inner.target_system),
38176 Self::COMMAND_INT(inner) => Some(inner.target_system),
38177 Self::COMMAND_LONG(inner) => Some(inner.target_system),
38178 Self::FILE_TRANSFER_PROTOCOL(inner) => Some(inner.target_system),
38179 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(inner) => Some(inner.target_system),
38180 Self::GIMBAL_DEVICE_SET_ATTITUDE(inner) => Some(inner.target_system),
38181 Self::GIMBAL_MANAGER_SET_ATTITUDE(inner) => Some(inner.target_system),
38182 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(inner) => Some(inner.target_system),
38183 Self::GIMBAL_MANAGER_SET_PITCHYAW(inner) => Some(inner.target_system),
38184 Self::GPS_INJECT_DATA(inner) => Some(inner.target_system),
38185 Self::LOGGING_ACK(inner) => Some(inner.target_system),
38186 Self::LOGGING_DATA(inner) => Some(inner.target_system),
38187 Self::LOGGING_DATA_ACKED(inner) => Some(inner.target_system),
38188 Self::LOG_ERASE(inner) => Some(inner.target_system),
38189 Self::LOG_REQUEST_DATA(inner) => Some(inner.target_system),
38190 Self::LOG_REQUEST_END(inner) => Some(inner.target_system),
38191 Self::LOG_REQUEST_LIST(inner) => Some(inner.target_system),
38192 Self::MISSION_ACK(inner) => Some(inner.target_system),
38193 Self::MISSION_CLEAR_ALL(inner) => Some(inner.target_system),
38194 Self::MISSION_COUNT(inner) => Some(inner.target_system),
38195 Self::MISSION_ITEM(inner) => Some(inner.target_system),
38196 Self::MISSION_ITEM_INT(inner) => Some(inner.target_system),
38197 Self::MISSION_REQUEST(inner) => Some(inner.target_system),
38198 Self::MISSION_REQUEST_INT(inner) => Some(inner.target_system),
38199 Self::MISSION_REQUEST_LIST(inner) => Some(inner.target_system),
38200 Self::MISSION_REQUEST_PARTIAL_LIST(inner) => Some(inner.target_system),
38201 Self::MISSION_SET_CURRENT(inner) => Some(inner.target_system),
38202 Self::MISSION_WRITE_PARTIAL_LIST(inner) => Some(inner.target_system),
38203 Self::OPEN_DRONE_ID_AUTHENTICATION(inner) => Some(inner.target_system),
38204 Self::OPEN_DRONE_ID_BASIC_ID(inner) => Some(inner.target_system),
38205 Self::OPEN_DRONE_ID_LOCATION(inner) => Some(inner.target_system),
38206 Self::OPEN_DRONE_ID_MESSAGE_PACK(inner) => Some(inner.target_system),
38207 Self::OPEN_DRONE_ID_OPERATOR_ID(inner) => Some(inner.target_system),
38208 Self::OPEN_DRONE_ID_SELF_ID(inner) => Some(inner.target_system),
38209 Self::OPEN_DRONE_ID_SYSTEM(inner) => Some(inner.target_system),
38210 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(inner) => Some(inner.target_system),
38211 Self::PARAM_EXT_REQUEST_LIST(inner) => Some(inner.target_system),
38212 Self::PARAM_EXT_REQUEST_READ(inner) => Some(inner.target_system),
38213 Self::PARAM_EXT_SET(inner) => Some(inner.target_system),
38214 Self::PARAM_MAP_RC(inner) => Some(inner.target_system),
38215 Self::PARAM_REQUEST_LIST(inner) => Some(inner.target_system),
38216 Self::PARAM_REQUEST_READ(inner) => Some(inner.target_system),
38217 Self::PARAM_SET(inner) => Some(inner.target_system),
38218 Self::PING(inner) => Some(inner.target_system),
38219 Self::PLAY_TUNE(inner) => Some(inner.target_system),
38220 Self::PLAY_TUNE_V2(inner) => Some(inner.target_system),
38221 Self::RC_CHANNELS_OVERRIDE(inner) => Some(inner.target_system),
38222 Self::REQUEST_DATA_STREAM(inner) => Some(inner.target_system),
38223 Self::REQUEST_EVENT(inner) => Some(inner.target_system),
38224 Self::RESPONSE_EVENT_ERROR(inner) => Some(inner.target_system),
38225 Self::SAFETY_SET_ALLOWED_AREA(inner) => Some(inner.target_system),
38226 Self::SERIAL_CONTROL(inner) => Some(inner.target_system),
38227 Self::SETUP_SIGNING(inner) => Some(inner.target_system),
38228 Self::SET_ACTUATOR_CONTROL_TARGET(inner) => Some(inner.target_system),
38229 Self::SET_ATTITUDE_TARGET(inner) => Some(inner.target_system),
38230 Self::SET_GPS_GLOBAL_ORIGIN(inner) => Some(inner.target_system),
38231 Self::SET_HOME_POSITION(inner) => Some(inner.target_system),
38232 Self::SET_MODE(inner) => Some(inner.target_system),
38233 Self::SET_POSITION_TARGET_GLOBAL_INT(inner) => Some(inner.target_system),
38234 Self::SET_POSITION_TARGET_LOCAL_NED(inner) => Some(inner.target_system),
38235 Self::SUPPORTED_TUNES(inner) => Some(inner.target_system),
38236 Self::TIMESYNC(inner) => Some(inner.target_system),
38237 Self::TUNNEL(inner) => Some(inner.target_system),
38238 Self::V2_EXTENSION(inner) => Some(inner.target_system),
38239 _ => None,
38240 }
38241 }
38242 fn target_component_id(&self) -> Option<u8> {
38243 match self {
38244 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(inner) => Some(inner.target_component),
38245 Self::CANFD_FRAME(inner) => Some(inner.target_component),
38246 Self::CAN_FILTER_MODIFY(inner) => Some(inner.target_component),
38247 Self::CAN_FRAME(inner) => Some(inner.target_component),
38248 Self::COMMAND_ACK(inner) => Some(inner.target_component),
38249 Self::COMMAND_CANCEL(inner) => Some(inner.target_component),
38250 Self::COMMAND_INT(inner) => Some(inner.target_component),
38251 Self::COMMAND_LONG(inner) => Some(inner.target_component),
38252 Self::FILE_TRANSFER_PROTOCOL(inner) => Some(inner.target_component),
38253 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(inner) => Some(inner.target_component),
38254 Self::GIMBAL_DEVICE_SET_ATTITUDE(inner) => Some(inner.target_component),
38255 Self::GIMBAL_MANAGER_SET_ATTITUDE(inner) => Some(inner.target_component),
38256 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(inner) => Some(inner.target_component),
38257 Self::GIMBAL_MANAGER_SET_PITCHYAW(inner) => Some(inner.target_component),
38258 Self::GPS_INJECT_DATA(inner) => Some(inner.target_component),
38259 Self::LOGGING_ACK(inner) => Some(inner.target_component),
38260 Self::LOGGING_DATA(inner) => Some(inner.target_component),
38261 Self::LOGGING_DATA_ACKED(inner) => Some(inner.target_component),
38262 Self::LOG_ERASE(inner) => Some(inner.target_component),
38263 Self::LOG_REQUEST_DATA(inner) => Some(inner.target_component),
38264 Self::LOG_REQUEST_END(inner) => Some(inner.target_component),
38265 Self::LOG_REQUEST_LIST(inner) => Some(inner.target_component),
38266 Self::MISSION_ACK(inner) => Some(inner.target_component),
38267 Self::MISSION_CLEAR_ALL(inner) => Some(inner.target_component),
38268 Self::MISSION_COUNT(inner) => Some(inner.target_component),
38269 Self::MISSION_ITEM(inner) => Some(inner.target_component),
38270 Self::MISSION_ITEM_INT(inner) => Some(inner.target_component),
38271 Self::MISSION_REQUEST(inner) => Some(inner.target_component),
38272 Self::MISSION_REQUEST_INT(inner) => Some(inner.target_component),
38273 Self::MISSION_REQUEST_LIST(inner) => Some(inner.target_component),
38274 Self::MISSION_REQUEST_PARTIAL_LIST(inner) => Some(inner.target_component),
38275 Self::MISSION_SET_CURRENT(inner) => Some(inner.target_component),
38276 Self::MISSION_WRITE_PARTIAL_LIST(inner) => Some(inner.target_component),
38277 Self::OPEN_DRONE_ID_AUTHENTICATION(inner) => Some(inner.target_component),
38278 Self::OPEN_DRONE_ID_BASIC_ID(inner) => Some(inner.target_component),
38279 Self::OPEN_DRONE_ID_LOCATION(inner) => Some(inner.target_component),
38280 Self::OPEN_DRONE_ID_MESSAGE_PACK(inner) => Some(inner.target_component),
38281 Self::OPEN_DRONE_ID_OPERATOR_ID(inner) => Some(inner.target_component),
38282 Self::OPEN_DRONE_ID_SELF_ID(inner) => Some(inner.target_component),
38283 Self::OPEN_DRONE_ID_SYSTEM(inner) => Some(inner.target_component),
38284 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(inner) => Some(inner.target_component),
38285 Self::PARAM_EXT_REQUEST_LIST(inner) => Some(inner.target_component),
38286 Self::PARAM_EXT_REQUEST_READ(inner) => Some(inner.target_component),
38287 Self::PARAM_EXT_SET(inner) => Some(inner.target_component),
38288 Self::PARAM_MAP_RC(inner) => Some(inner.target_component),
38289 Self::PARAM_REQUEST_LIST(inner) => Some(inner.target_component),
38290 Self::PARAM_REQUEST_READ(inner) => Some(inner.target_component),
38291 Self::PARAM_SET(inner) => Some(inner.target_component),
38292 Self::PING(inner) => Some(inner.target_component),
38293 Self::PLAY_TUNE(inner) => Some(inner.target_component),
38294 Self::PLAY_TUNE_V2(inner) => Some(inner.target_component),
38295 Self::RC_CHANNELS_OVERRIDE(inner) => Some(inner.target_component),
38296 Self::REQUEST_DATA_STREAM(inner) => Some(inner.target_component),
38297 Self::REQUEST_EVENT(inner) => Some(inner.target_component),
38298 Self::RESPONSE_EVENT_ERROR(inner) => Some(inner.target_component),
38299 Self::SAFETY_SET_ALLOWED_AREA(inner) => Some(inner.target_component),
38300 Self::SERIAL_CONTROL(inner) => Some(inner.target_component),
38301 Self::SETUP_SIGNING(inner) => Some(inner.target_component),
38302 Self::SET_ACTUATOR_CONTROL_TARGET(inner) => Some(inner.target_component),
38303 Self::SET_ATTITUDE_TARGET(inner) => Some(inner.target_component),
38304 Self::SET_POSITION_TARGET_GLOBAL_INT(inner) => Some(inner.target_component),
38305 Self::SET_POSITION_TARGET_LOCAL_NED(inner) => Some(inner.target_component),
38306 Self::SUPPORTED_TUNES(inner) => Some(inner.target_component),
38307 Self::TIMESYNC(inner) => Some(inner.target_component),
38308 Self::TUNNEL(inner) => Some(inner.target_component),
38309 Self::V2_EXTENSION(inner) => Some(inner.target_component),
38310 _ => None,
38311 }
38312 }
38313}